From 6e5b115412043284cdb973d21a2a5da38af51bb2 Mon Sep 17 00:00:00 2001 From: nh17000 <46301909+nh17000@users.noreply.github.com> Date: Sat, 3 May 2025 12:48:51 -0500 Subject: [PATCH 01/58] Simulate Elevator Hardware abstract the elevator; example for refactoring other subsystems --- .gitignore | 4 +- .vscode/launch.json | 18 + simgui-ds.json | 126 ++++++ simgui-window.json | 108 +++++ simgui.json | 91 ++++ src/main/java/frc/robot/Constants.java | 33 +- src/main/java/frc/robot/Robot.java | 15 +- src/main/java/frc/robot/RobotContainer.java | 19 +- .../java/frc/robot/commands/AutoAlign.java | 4 +- .../java/frc/robot/commands/ElevatorHold.java | 7 +- .../java/frc/robot/subsystems/Climber.java | 17 +- .../java/frc/robot/subsystems/Elevator.java | 427 ------------------ .../robot/subsystems/Elevator/Elevator.java | 203 +++++++++ .../robot/subsystems/Elevator/ElevatorIO.java | 24 + .../subsystems/Elevator/ElevatorIOReal.java | 98 ++++ .../subsystems/Elevator/ElevatorIOSim.java | 118 +++++ .../subsystems/Elevator/MechVisualizer.java | 96 ++++ 17 files changed, 957 insertions(+), 451 deletions(-) create mode 100644 .vscode/launch.json create mode 100644 simgui-ds.json create mode 100644 simgui-window.json create mode 100644 simgui.json delete mode 100644 src/main/java/frc/robot/subsystems/Elevator.java create mode 100644 src/main/java/frc/robot/subsystems/Elevator/Elevator.java create mode 100644 src/main/java/frc/robot/subsystems/Elevator/ElevatorIO.java create mode 100644 src/main/java/frc/robot/subsystems/Elevator/ElevatorIOReal.java create mode 100644 src/main/java/frc/robot/subsystems/Elevator/ElevatorIOSim.java create mode 100644 src/main/java/frc/robot/subsystems/Elevator/MechVisualizer.java diff --git a/.gitignore b/.gitignore index d012c1d..a5b7765 100644 --- a/.gitignore +++ b/.gitignore @@ -170,8 +170,8 @@ out/ # Simulation GUI and other tools window save file networktables.json -simgui*.json -*-window.json +# simgui*.json +# *-window.json # Simulation data log directory logs/ diff --git a/.vscode/launch.json b/.vscode/launch.json new file mode 100644 index 0000000..f2805d9 --- /dev/null +++ b/.vscode/launch.json @@ -0,0 +1,18 @@ +{ + "version": "0.2.0", + "configurations": [ + { + "type": "java", + "name": "Current File", + "request": "launch", + "mainClass": "${file}" + }, + { + "type": "java", + "name": "Main", + "request": "launch", + "mainClass": "frc.robot.Main", + "projectName": "2025RobotCode" + } + ] +} diff --git a/simgui-ds.json b/simgui-ds.json new file mode 100644 index 0000000..9f898d1 --- /dev/null +++ b/simgui-ds.json @@ -0,0 +1,126 @@ +{ + "Keyboard 0 Settings": { + "window": { + "visible": true + } + }, + "Keyboard 1 Settings": { + "window": { + "visible": true + } + }, + "keyboardJoysticks": [ + { + "axisConfig": [ + { + "decKey": 65, + "incKey": 68 + }, + { + "decKey": 87, + "incKey": 83 + }, + { + "incKey": 49 + }, + { + "incKey": 51 + }, + { + "decKey": 74, + "incKey": 76 + }, + { + "decKey": 73, + "incKey": 75 + } + ], + "axisCount": 6, + "buttonCount": 8, + "buttonKeys": [ + 90, + 88, + 67, + 86, + 81, + 69, + -1, + 266, + -1, + -1 + ], + "povConfig": [ + { + "key0": 265, + "key180": 264, + "key270": 263, + "key90": 262 + } + ], + "povCount": 1 + }, + { + "axisConfig": [ + {}, + { + "decKey": 89, + "incKey": 85 + }, + {}, + {}, + { + "decKey": 80, + "incKey": 79 + } + ], + "axisCount": 5, + "buttonCount": 8, + "buttonKeys": [ + 77, + 44, + 46, + 47, + -1, + -1, + -1, + 267 + ], + "povConfig": [ + { + "key0": 84, + "key180": 71, + "key270": 70, + "key90": 72 + } + ], + "povCount": 1 + }, + { + "axisCount": 2, + "buttonCount": 6, + "buttonKeys": [ + 260, + 268, + -1, + -1, + 269, + -1 + ], + "povCount": 0 + }, + { + "axisCount": 0, + "buttonCount": 0, + "povCount": 0 + } + ], + "robotJoysticks": [ + { + "guid": "Keyboard0" + }, + { + "guid": "Keyboard1" + } + ], + "useEnableDisableHotkeys": true +} diff --git a/simgui-window.json b/simgui-window.json new file mode 100644 index 0000000..52b5d5d --- /dev/null +++ b/simgui-window.json @@ -0,0 +1,108 @@ +{ + "Docking": { + "Data": [] + }, + "MainWindow": { + "GLOBAL": { + "font": "Proggy Dotted", + "fps": "120", + "height": "1046", + "maximized": "1", + "style": "0", + "userScale": "2", + "width": "1920", + "xpos": "0", + "ypos": "34" + } + }, + "Table": { + "0xE56EC1C2,4": { + "Column 0 Weight": "1.0000", + "Column 1 Weight": "1.0000", + "Column 2 Weight": "1.0000", + "Column 3 Weight": "1.0000" + } + }, + "Window": { + "###/SmartDashboard/Auto Mode": { + "Collapsed": "0", + "Pos": "162,101", + "Size": "363,62" + }, + "###/SmartDashboard/Elevator Sim": { + "Collapsed": "0", + "Pos": "532,30", + "Size": "357,694" + }, + "###/SmartDashboard/Module 0": { + "Collapsed": "0", + "Pos": "400,400", + "Size": "311,200" + }, + "###Addressable LEDs": { + "Collapsed": "0", + "Pos": "290,100", + "Size": "332,246" + }, + "###FMS": { + "Collapsed": "0", + "Pos": "8,699", + "Size": "233,258" + }, + "###Joysticks": { + "Collapsed": "0", + "Pos": "292,408", + "Size": "1156,291" + }, + "###Keyboard 0 Settings": { + "Collapsed": "0", + "Pos": "985,23", + "Size": "300,560" + }, + "###Keyboard 1 Settings": { + "Collapsed": "0", + "Pos": "1299,27", + "Size": "300,560" + }, + "###NetworkTables": { + "Collapsed": "0", + "Pos": "433,697", + "Size": "1125,349" + }, + "###NetworkTables Info": { + "Collapsed": "0", + "Pos": "324,317", + "Size": "1125,217" + }, + "###Other Devices": { + "Collapsed": "0", + "Pos": "1481,312", + "Size": "375,352" + }, + "###Plot <0>": { + "Collapsed": "0", + "Pos": "60,428", + "Size": "700,32" + }, + "###System Joysticks": { + "Collapsed": "0", + "Pos": "0,399", + "Size": "273,308" + }, + "###Timing": { + "Collapsed": "0", + "Pos": "1,180", + "Size": "199,213" + }, + "Debug##Default": { + "Collapsed": "0", + "Pos": "60,60", + "Size": "400,400" + }, + "Robot State": { + "Collapsed": "0", + "Pos": "5,20", + "Size": "143,158" + } + } +} diff --git a/simgui.json b/simgui.json new file mode 100644 index 0000000..1ad037b --- /dev/null +++ b/simgui.json @@ -0,0 +1,91 @@ +{ + "HALProvider": { + "Addressable LEDs": { + "0": { + "columns": 20 + } + }, + "Other Devices": { + "window": { + "visible": false + } + } + }, + "NTProvider": { + "types": { + "/AdvantageKit/RealOutputs/Alerts": "Alerts", + "/FMSInfo": "FMSInfo", + "/Pose": "Field2d", + "/SmartDashboard/Alerts": "Alerts", + "/SmartDashboard/Auto Mode": "String Chooser", + "/SmartDashboard/Elevator Sim": "Mechanism2d", + "/SmartDashboard/Module 0": "Mechanism2d", + "/SmartDashboard/Module 1": "Mechanism2d", + "/SmartDashboard/Module 2": "Mechanism2d", + "/SmartDashboard/Module 3": "Mechanism2d" + }, + "windows": { + "/SmartDashboard/Auto Mode": { + "window": { + "visible": true + } + }, + "/SmartDashboard/Elevator Sim": { + "window": { + "visible": true + } + } + } + }, + "NetworkTables": { + "Persistent Values": { + "open": false + }, + "Retained Values": { + "open": false + }, + "transitory": { + "AdvantageKit": { + "Elevator": { + "open": true + }, + "RealOutputs": { + "Elevator": { + "open": true + }, + "open": true + }, + "open": true + } + } + }, + "Plot": { + "Plot <0>": { + "plots": [ + { + "backgroundColor": [ + 0.0, + 0.0, + 0.0, + 0.8500000238418579 + ], + "height": -42, + "series": [ + { + "color": [ + 0.2980392277240753, + 0.44705885648727417, + 0.6901960968971252, + 1.0 + ], + "id": "NT:/AdvantageKit/Elevator/AppliedVolts" + } + ] + } + ], + "window": { + "visible": false + } + } + } +} diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 5827652..dbfc467 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -13,6 +13,7 @@ import edu.wpi.first.units.measure.Dimensionless; import edu.wpi.first.units.measure.Frequency; import edu.wpi.first.units.measure.Time; +import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; public class Constants { @@ -118,7 +119,6 @@ public static final class AlignConstants { } public static final class ElevatorConstants { - public static final int ELEVATOR_ID = 21; public static final int ELEVATOR_FOLLOWER_ID = 20; public static final NeutralModeValue MODE = NeutralModeValue.Brake; @@ -288,4 +288,35 @@ public static final class LEDConstants { public static final Dimensionless BLINK_BRIGHTNESS = Percent.of(50); public static final Time BREATHE_PERIOD = Seconds.of(1); } + + public static class SimulationConstants { + public static final boolean SIMULATE_GRAVITY = true; + + public static final double ARM_GEARING = 15; + public static final double ARM_MASS = Units.lbsToKilograms(4); + public static final double ARM_LENGTH = Units.inchesToMeters(12); + public static final double ARM_MOI = SingleJointedArmSim.estimateMOI(ARM_LENGTH, ARM_MASS); + public static final double MIN_ANGLE = Units.degreesToRadians(-180); + public static final double MAX_ANGLE = Units.degreesToRadians(180); + public static final double STARTING_ANGLE = Units.degreesToRadians(-90); + + // joint of ee to bottom of coral + public static final double CAM_LENGTH = Units.inchesToMeters(14.5); + + // joint of ee to top plane of coral + public static final double EE_TO_CORAL_HEIGHT = Units.inchesToMeters(2.5); + public static final double EE_TO_CORAL_WIDTH = Units.inchesToMeters(4.25); + public static final double CORAL_LENGTH = Units.inchesToMeters(11.875); + + public static final double CARRIAGE_MASS_KG = 4.2; + public static final double DRUM_RADIUS_METERS = Units.inchesToMeters(ElevatorConstants.PULLEY_DIAMETER / 2.0); + public static final double MIN_HEIGHT = Units.inchesToMeters(0); + public static final double MAX_HEIGHT = MIN_HEIGHT + Units.inchesToMeters(ElevatorConstants.BARGE_HEIGHT + 1); + public static final double STARTING_HEIGHT = MIN_HEIGHT; + + // new EE viz + public static final double PIVOT_TO_MIDDLE_OF_CORAL_ANG_OFFSET = Units.degreesToRadians(-20.2531597269); + public static final double PIVOT_TO_MIDDLE_OF_CORAL_RADIUS = Units.inchesToMeters(23.249031544); + public static final double PIVOT_ANGLE_TO_CORAL_ANGLE = Units.degreesToRadians(243.986); + } } diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index 1546f88..b9015e2 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -6,6 +6,7 @@ import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; +import frc.robot.subsystems.Elevator.MechVisualizer; import org.littletonrobotics.junction.LogFileUtil; import org.littletonrobotics.junction.LoggedRobot; import org.littletonrobotics.junction.Logger; @@ -19,13 +20,15 @@ public class Robot extends LoggedRobot { private final RobotContainer m_robotContainer; public Robot() { - m_robotContainer = new RobotContainer(); Logger.recordMetadata("2025RobotCode", "Comp Bot Code"); // Set a metadata value - if (isReal()) { + boolean isReplay = false; + if (isReal()) { // REAL Logger.addDataReceiver(new WPILOGWriter("/media/sda1/")); // Log to a USB stick ("/U/logs") Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables - } else { + } else if (!isReplay) { // SIM + Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables + } else { // REPLAY setUseTiming(false); // Run as fast as possible String logPath = // "/media/sda1/"; LogFileUtil.findReplayLog(); // Pull the replay log from AdvantageScope (or prompt the user) @@ -35,6 +38,8 @@ public Robot() { } Logger.start(); + + m_robotContainer = new RobotContainer(); } @Override @@ -92,5 +97,7 @@ public void testPeriodic() {} public void testExit() {} @Override - public void simulationPeriodic() {} + public void simulationPeriodic() { + MechVisualizer.getInstance().periodic(); + } } diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index c55ac16..52dd501 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -31,7 +31,9 @@ import frc.robot.subsystems.Arm.ArmMode; import frc.robot.subsystems.Climber; import frc.robot.subsystems.CommandSwerveDrivetrain; -import frc.robot.subsystems.Elevator; +import frc.robot.subsystems.Elevator.Elevator; +import frc.robot.subsystems.Elevator.ElevatorIOReal; +import frc.robot.subsystems.Elevator.ElevatorIOSim; import frc.robot.subsystems.EndEffector; import frc.robot.util.vision.PoseEstimation; @@ -39,7 +41,7 @@ public class RobotContainer { private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); - public static final Elevator elevator = Elevator.getInstance(); + private Elevator elevator; public static final Arm arm = Arm.getInstance(); public static final EndEffector endEffector = EndEffector.getInstance(); public static final Climber climber = Climber.getInstance(); @@ -106,6 +108,12 @@ public class RobotContainer { public final SendableChooser autoChooser; public RobotContainer() { + if (Robot.isReal()) { + elevator = new Elevator(new ElevatorIOReal()); + } else { + elevator = new Elevator(new ElevatorIOSim()); + } + setDefaultCommands(); registerNamedCommands(); autoChooser = AutoBuilder.buildAutoChooser("2R_EF-L4"); @@ -238,6 +246,11 @@ private void configureBindings() { .andThen(new InstantCommand(() -> endEffector.setAlgae()))); climberAdjustUp_PovUp + .onTrue(new InstantCommand(() -> { + elevator.setElevatorStowedMode(); + arm.setAlgae(); + arm.setStowed(); + })) .whileTrue(new RunCommand(() -> climber.climberUp())) .onFalse(new InstantCommand(() -> climber.stop())); climberAdjustDown_PovDown @@ -423,7 +436,7 @@ public void setDefaultCommands() { * drivetrain.getSpeedMultipler()) .withRotationalRate(drivetrain.turnLimiter.calculate(-driverController.getRightX()) * MaxAngularRate))); - elevator.setDefaultCommand(new ElevatorHold()); + elevator.setDefaultCommand(new ElevatorHold(elevator)); arm.setDefaultCommand(new ArmHold()); // climber.setDefaultCommand(new ClimbCommand()); // ledstrip.setDefaultCommand(ledstrip.defaultCommand(() -> endEffector.isCoral())); diff --git a/src/main/java/frc/robot/commands/AutoAlign.java b/src/main/java/frc/robot/commands/AutoAlign.java index 57650b5..d22dc31 100644 --- a/src/main/java/frc/robot/commands/AutoAlign.java +++ b/src/main/java/frc/robot/commands/AutoAlign.java @@ -144,7 +144,7 @@ public double getAlignStrafeSpeedPercent(double setPoint, int tagID, String llNa // 3D transform of the robot in the coordinate system of the primary in-view AprilTag // (array (6)) [tx, ty, tz, pitch, yaw, roll] (meters, degrees) double[] targetRelativeRobotPose = LimelightHelpers.getBotPose_TargetSpace(llName); - double tx = targetRelativeRobotPose[0]; + double tx = targetRelativeRobotPose.length > 0 ? targetRelativeRobotPose[0] : 0; double txError = tx - setPoint; Transform2d offset = poseSupplier.get().minus(getTagPose(tagID)); @@ -199,7 +199,7 @@ public double getAlignRotationSpeedPercent(Rotation2d targetAngle2d) { public double getAlignForwardSpeedPercent(double setPoint, int tagID, String llName) { double[] targetRelativeRobotPose = LimelightHelpers.getBotPose_TargetSpace(llName); - double tz = targetRelativeRobotPose[2]; + double tz = targetRelativeRobotPose.length > 2 ? targetRelativeRobotPose[2] : 0; double tzError = tz - setPoint; Transform2d offset = poseSupplier.get().minus(getTagPose(tagID)); diff --git a/src/main/java/frc/robot/commands/ElevatorHold.java b/src/main/java/frc/robot/commands/ElevatorHold.java index bd72e84..e28519f 100644 --- a/src/main/java/frc/robot/commands/ElevatorHold.java +++ b/src/main/java/frc/robot/commands/ElevatorHold.java @@ -5,15 +5,16 @@ package frc.robot.commands; import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.subsystems.Elevator; +import frc.robot.subsystems.Elevator.Elevator; /* You should consider using the more terse Command factories API instead https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands */ public class ElevatorHold extends Command { - private Elevator elevator = Elevator.getInstance(); + private Elevator elevator; /** Creates a new ElevatorHold. */ - public ElevatorHold() { + public ElevatorHold(Elevator elevator) { // Use addRequirements() here to declare subsystem dependencies. + this.elevator = elevator; addRequirements(elevator); } diff --git a/src/main/java/frc/robot/subsystems/Climber.java b/src/main/java/frc/robot/subsystems/Climber.java index fc5bc93..df043e7 100644 --- a/src/main/java/frc/robot/subsystems/Climber.java +++ b/src/main/java/frc/robot/subsystems/Climber.java @@ -19,7 +19,6 @@ public class Climber extends SubsystemBase { private static final Climber CLIMBER = new Climber(); private TalonFXConfiguration talonFXConfigs; - private static final Elevator ELEVATOR = Elevator.getInstance(); private static final Arm ARM = Arm.getInstance(); private double setpoint = ClimbConstants.CLIMB_SETPOINT; @@ -84,13 +83,13 @@ public void climberAdjustDown() { climberOffset -= 10; } - public void prepClimber() { - if (climbState != 0) { - ELEVATOR.setElevatorStowedMode(); - ARM.setAlgae(); - ARM.setStowed(); - } - } + // public void prepClimber() { + // if (climbState != 0) { + // ELEVATOR.setElevatorStowedMode(); + // ARM.setAlgae(); + // ARM.setStowed(); + // } + // } public void zeroClimber() { climbMotor.setPosition(0); @@ -143,7 +142,7 @@ public void climbClimber() { public void incrementClimbState() { climbState = Math.min(2, climbState + 1); - prepClimber(); + // prepClimber(); setClimbPosition(); } diff --git a/src/main/java/frc/robot/subsystems/Elevator.java b/src/main/java/frc/robot/subsystems/Elevator.java deleted file mode 100644 index 66da8e1..0000000 --- a/src/main/java/frc/robot/subsystems/Elevator.java +++ /dev/null @@ -1,427 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package frc.robot.subsystems; - -import static edu.wpi.first.units.Units.*; - -import com.ctre.phoenix6.BaseStatusSignal; -import com.ctre.phoenix6.SignalLogger; -import com.ctre.phoenix6.configs.TalonFXConfiguration; -import com.ctre.phoenix6.controls.Follower; -import com.ctre.phoenix6.controls.MotionMagicVoltage; -import com.ctre.phoenix6.controls.VoltageOut; -import com.ctre.phoenix6.signals.GravityTypeValue; -import edu.wpi.first.wpilibj.DriverStation; -import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.SubsystemBase; -import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; -import frc.lib.drivers.PearadoxTalonFX; -import frc.robot.Constants.ArmConstants; -import frc.robot.Constants.ElevatorConstants; -import frc.robot.util.SmarterDashboard; - -public class Elevator extends SubsystemBase { - - private PearadoxTalonFX elevator; - private PearadoxTalonFX elevatorFollower; - private MotionMagicVoltage motionMagicRequest = new MotionMagicVoltage(0); - private double elevatorOffset = 0.0; - private TalonFXConfiguration talonFXConfigs = new TalonFXConfiguration(); - - private boolean isCoral = true; - private boolean isAligning = false; - private boolean isZeroing = false; - - public static enum ElevatorMode { - STOWED, - STATION, - LEVEL_TWO, - LEVEL_THREE, - LEVEL_FOUR, - ALGAE_LOW, - ALGAE_HIGH, - BARGE, - } - - private ElevatorMode elevatorMode = ElevatorMode.STOWED; - // private double lowest_rot = ElevatorConstants.STOWED_ROT; - // private double highest_rot = ElevatorConstants.MAX_ELEVATOR_ROT; - - private boolean isLowering = false; - - private static Elevator ELEVATOR = new Elevator(); - - public static Elevator getInstance() { - return ELEVATOR; - } - - private final VoltageOut m_voltReq = new VoltageOut(0.0); - - private final SysIdRoutine m_sysIdRoutineTranslation = new SysIdRoutine( - new SysIdRoutine.Config( - null, // Use default ramp rate (1 V/s) - Volts.of(4), // Reduce dynamic step voltage to 4 V to prevent brownout - null, // Use default timeout (10 s) - // Log state with SignalLogger class - state -> SignalLogger.writeString("SysIdTranslation_State", state.toString())), - new SysIdRoutine.Mechanism( - (volts) -> elevator.setControl(m_voltReq.withOutput(volts.in(Volts))), null, this)); - - public Command sysIdQuasistatic(SysIdRoutine.Direction direction) { - return m_sysIdRoutineTranslation.quasistatic(direction); - } - - public Command sysIdDynamic(SysIdRoutine.Direction direction) { - return m_sysIdRoutineTranslation.dynamic(direction); - } - - /** Creates a new Elevator. */ - public Elevator() { - elevator = new PearadoxTalonFX( - ElevatorConstants.ELEVATOR_ID, - ElevatorConstants.MODE, - ElevatorConstants.CURRENT_LIMIT, - ElevatorConstants.IS_INVERTED); - - elevatorFollower = new PearadoxTalonFX( - ElevatorConstants.ELEVATOR_FOLLOWER_ID, - ElevatorConstants.MODE, - ElevatorConstants.CURRENT_LIMIT, - ElevatorConstants.IS_INVERTED); - - var slot0Configs = talonFXConfigs.Slot0; - slot0Configs.kG = ElevatorConstants.kG; // add enough Gravity Gain just before motor starts moving - slot0Configs.kS = ElevatorConstants.kS; // Add 0.1 V output to overcome static friction - slot0Configs.kV = ElevatorConstants.kV; // A velocity target of 1 rps results in 0.1 V output - slot0Configs.kA = ElevatorConstants.kA; // An acceleration of 1 rps/s requires 0.01 V output - slot0Configs.kP = ElevatorConstants.kP; // A position error of 2.5 rotations results in 12 V output, prev 4.8 - slot0Configs.kI = ElevatorConstants.kI; // no output for integrated error - slot0Configs.kD = ElevatorConstants.kD; // A velocity error of 1 rps results in 0.1 V output - - var slot1Configs = talonFXConfigs.Slot1; - slot1Configs.kG = ElevatorConstants.kG; // add enough Gravity Gain just before motor starts moving - slot1Configs.kS = ElevatorConstants.kS; // Add 0.1 V output to overcome static friction - slot1Configs.kV = ElevatorConstants.kV; // A velocity target of 1 rps results in 0.1 V output - slot1Configs.kA = ElevatorConstants.kA; // An acceleration of 1 rps/s requires 0.01 V output - slot1Configs.kP = ElevatorConstants.kP; // A position error of 2.5 rotations results in 12 V output, prev 4.8 - slot1Configs.kI = ElevatorConstants.kI; // no output for integrated error - slot1Configs.kD = ElevatorConstants.kD; // A velocity error of 1 rps results in 0.1 V output - - var motionMagicConfigs = talonFXConfigs.MotionMagic; - motionMagicConfigs.MotionMagicCruiseVelocity = - ElevatorConstants.MM_CRUISE_VELCOCITY_UP; // Target cruise velocity of 80 rps - motionMagicConfigs.MotionMagicAcceleration = - ElevatorConstants.MM_ACCELERATION_UP; // Target acceleration of 160 rps/s (0.5 seconds) - // (not sure if needed - > ) motionMagicConfigs.MotionMagicJerk = 1600; // Target jerk of 1600 rps/s/s (0.1 - // seconds) - - talonFXConfigs.SoftwareLimitSwitch.ForwardSoftLimitEnable = true; - talonFXConfigs.SoftwareLimitSwitch.ForwardSoftLimitThreshold = - 33 * ElevatorConstants.GEAR_RATIO / (Math.PI * ElevatorConstants.PULLEY_DIAMETER); - talonFXConfigs.SoftwareLimitSwitch.ReverseSoftLimitEnable = true; - talonFXConfigs.SoftwareLimitSwitch.ReverseSoftLimitThreshold = 0; - talonFXConfigs.Slot0.GravityType = GravityTypeValue.Elevator_Static; - - elevator.getConfigurator().apply(talonFXConfigs); - - // elevator.getPosition().setUpdateFrequency(ElevatorConstants.UPDATE_FREQ); - // elevator.getVelocity().setUpdateFrequency(ElevatorConstants.UPDATE_FREQ); - - // // These are needed for the follower motor to work - // elevator.getDutyCycle().setUpdateFrequency(ElevatorConstants.UPDATE_FREQ); - // elevator.getMotorVoltage().setUpdateFrequency(ElevatorConstants.UPDATE_FREQ); - // elevator.getTorqueCurrent().setUpdateFrequency(ElevatorConstants.UPDATE_FREQ); - // elevator.getSupplyCurrent().setUpdateFrequency(ElevatorConstants.UPDATE_FREQ); - // elevator.getStatorCurrent().setUpdateFrequency(ElevatorConstants.UPDATE_FREQ); - - BaseStatusSignal.setUpdateFrequencyForAll( - ArmConstants.UPDATE_FREQ, - elevator.getPosition(), - elevator.getVelocity(), - elevator.getDutyCycle(), - elevator.getMotorVoltage(), - elevator.getTorqueCurrent(), - elevator.getSupplyCurrent(), - elevator.getStatorCurrent()); - - elevator.optimizeBusUtilization(); - - elevatorFollower.getConfigurator().apply(talonFXConfigs); - elevatorFollower.optimizeBusUtilization(); - elevatorFollower.setControl(new Follower(ElevatorConstants.ELEVATOR_ID, true)); - - // SmarterDashboard.putNumber("Elevator kG", ElevatorConstants.kG); - // SmarterDashboard.putNumber("Elevator kS", ElevatorConstants.kS); - // SmarterDashboard.putNumber("Elevator kV", ElevatorConstants.kV); - // SmarterDashboard.putNumber("Elevator kA", ElevatorConstants.kA); - // SmarterDashboard.putNumber("Elevator kP", ElevatorConstants.kP); - // SmarterDashboard.putNumber("Elevator kI", ElevatorConstants.kI); - // SmarterDashboard.putNumber("Elevator kD", ElevatorConstants.kD); - } - - @Override - public void periodic() { - SmarterDashboard.putNumber("Elevator/Position Inches", getElevatorPositionInches()); - SmarterDashboard.putNumber("Elevator/Velocity (in/sec)", getElevatorVelocityInchesPerSecond()); - SmarterDashboard.putNumber("Elevator/Position Rots", getElevatorPositionRots()); - SmarterDashboard.putNumber("Elevator/Velocity (rot/sec)", getElevatorVelocity_RotsPerSecond()); - SmarterDashboard.putNumber( - "Elevator/Supply Current A", elevator.getSupplyCurrent().getValueAsDouble()); - SmarterDashboard.putNumber( - "Elevator/Stator Current A", elevator.getStatorCurrent().getValueAsDouble()); - SmarterDashboard.putNumber( - "Elevator/Voltage V", elevator.getMotorVoltage().getValueAsDouble()); - SmarterDashboard.putNumber("Elevator/Offset", elevatorOffset); - SmarterDashboard.putString("Elevator Mode", elevatorMode.toString()); - SmarterDashboard.putBoolean("Elevator/IsCoral", isCoral); - - // setAligning(!RobotContainer.align.isAligned()); - } - - public void setElevatorPosition() { - double setpoint = ElevatorConstants.STOWED_ROT + elevatorOffset; - // if (elevatorMode == ElevatorMode.STATION) { - // if (isCoral) { - // setpoint = ElevatorConstants.STATION_ROT + elevatorOffset; - // } else { - // setpoint = ElevatorConstants.STOWED_ROT + elevatorOffset; - // } - // } else if (elevatorMode == ElevatorMode.LEVEL_TWO) { - // if (isCoral) { - // setpoint = ElevatorConstants.LEVEL_TWO_ROT + elevatorOffset; - // } else { - // setpoint = ElevatorConstants.ALGAE_LOW_ROT + elevatorOffset; - // } - // } else if (elevatorMode == ElevatorMode.LEVEL_THREE) { - // if (isCoral) { - // setpoint = ElevatorConstants.LEVEL_THREE_ROT + elevatorOffset; - // } else { - // setpoint = ElevatorConstants.ALGAE_HIGH_ROT + elevatorOffset; - // } - // } else if (elevatorMode == ElevatorMode.LEVEL_FOUR) { - // setpoint = ElevatorConstants.LEVEL_FOUR_ROT + elevatorOffset; - // } else if (elevatorMode == ElevatorMode.ALGAE_LOW) { - // setpoint = ElevatorConstants.ALGAE_LOW_HEIGHT + elevatorOffset; - // } else if (elevatorMode == ElevatorMode.ALGAE_HIGH) { - // setpoint = ElevatorConstants.ALGAE_HIGH_HEIGHT + elevatorOffset; - // } else if (elevatorMode == ElevatorMode.BARGE) { - // setpoint = ElevatorConstants.BARGE_ROT + elevatorOffset; - // } - - if (elevatorMode == ElevatorMode.STOWED) { - // if (isCoral) { - setpoint = ElevatorConstants.STOWED_ROT + elevatorOffset; - // } else { - // setpoint = ElevatorConstants.STATION_ROT + elevatorOffset; - // ; - // } - } else if (elevatorMode == ElevatorMode.STATION) { - if (isAligning) { - setpoint = ElevatorConstants.OBSTRUCTED_STATION_ROT + elevatorOffset; - } else { - setpoint = ElevatorConstants.STATION_ROT + elevatorOffset; - } - } - if (isCoral) { - if (elevatorMode == ElevatorMode.LEVEL_TWO) { - setpoint = ElevatorConstants.LEVEL_TWO_ROT + elevatorOffset; - - } else if (elevatorMode == ElevatorMode.LEVEL_THREE) { - setpoint = ElevatorConstants.LEVEL_THREE_ROT + elevatorOffset; - } else if (elevatorMode == ElevatorMode.LEVEL_FOUR) { - if (isAligning) { - // setpoint = RobotContainer.align.getElevatorHeightRots() + elevatorOffset; - // setpoint = ElevatorConstants.BARGE_ROT + elevatorOffset; - setpoint = ElevatorConstants.LEVEL_FOUR_ROT + elevatorOffset; - - } else { - if (DriverStation.isAutonomous()) { - setpoint = ElevatorConstants.LEVEL_FOUR_ROT + elevatorOffset - 0.4; - } else { - setpoint = ElevatorConstants.LEVEL_FOUR_ROT + elevatorOffset; - } - } - } - } else if (!isCoral) { - if (elevatorMode == ElevatorMode.LEVEL_TWO) { - setpoint = ElevatorConstants.ALGAE_LOW_ROT + elevatorOffset; - } else if (elevatorMode == ElevatorMode.LEVEL_THREE) { - setpoint = ElevatorConstants.ALGAE_HIGH_ROT + elevatorOffset; - } else if (elevatorMode == ElevatorMode.LEVEL_FOUR) { - setpoint = ElevatorConstants.BARGE_ROT + elevatorOffset; - } - } - - // } else { // stowed - // setpoint = Math.max(lowest_rot, Math.min((ElevatorConstants.STOWED_ROT + elevatorOffset), highest_rot)); - // } - - // switch (elevatorMode) { - // case LEVEL_FOUR: setpoint = ElevatorConstants.LEVEL_FOUR_ROT + elevatorOffset; break; - // case LEVEL_THREE: setpoint = ElevatorConstants.LEVEL_THREE_ROT + elevatorOffset; break; - // case LEVEL_TWO: setpoint = ElevatorConstants.LEVEL_TWO_ROT + elevatorOffset; break; - // case STATION: setpoint = ElevatorConstants.STATION_ROT + elevatorOffset; break; - // default: setpoint = Math.max(lowest_rot, Math.min((ElevatorConstants.STOWED_ROT + elevatorOffset), - // highest_rot)); - // } - - isLowering = elevator.getPosition().getValueAsDouble() > setpoint; - - if (!isZeroing) { - elevator.setControl(motionMagicRequest.withPosition(setpoint).withSlot(isLowering ? 1 : 0)); - // elevator.setControl(new VoltageOut(elevatorOffset)); - } else { - homeElevator(); - } - - // // only reapply configs when this changes - // if (isLowering != (elevator.getPosition().getValueAsDouble() > setpoint)) { - // isLowering = elevator.getPosition().getValueAsDouble() > setpoint; - - // if (isLowering) { - // talonFXConfigs.MotionMagic.MotionMagicCruiseVelocity = ElevatorConstants.MM_CRUISE_VELCOCITY_DOWN; - // talonFXConfigs.MotionMagic.MotionMagicAcceleration = ElevatorConstants.MM_ACCELERATION_DOWN; - // } else { - // talonFXConfigs.MotionMagic.MotionMagicCruiseVelocity = ElevatorConstants.MM_CRUISE_VELCOCITY_UP; - // talonFXConfigs.MotionMagic.MotionMagicAcceleration = ElevatorConstants.MM_ACCELERATION_UP; - // } - - // elevator.getConfigurator().refresh(talonFXConfigs); - // elevator.getConfigurator().apply(talonFXConfigs); - - // SmarterDashboard.putBoolean("Elevator/IsLowering", isLowering); - // } - SmarterDashboard.putBoolean("Elevator/IsLowering", isLowering); - - SmarterDashboard.putNumber("Elevator/Setpoint", setpoint); - // Logger.recordOutput("Elevator/Align Setpoint", RobotContainer.align.getElevatorHeightRots() + - // elevatorOffset); - } - - public void homeElevator() { - elevator.set(ElevatorConstants.HOMING_SPEED); - } - - public void zeroElevator() { - SmarterDashboard.putNumber( - "Elevator/New Zero Diff", 0 - elevator.getPosition().getValueAsDouble()); - elevator.setPosition(0); - elevatorOffset = 0; - } - - public void stopElevator() { - elevator.set(0); - } - - // public double getAutoHeightAdjust(){ - // double angle = RobotContainer.arm.getAutoArmAngle(); - - // return - // } - - public double getElevatorPositionRots() { - return elevator.getPosition().getValueAsDouble(); - } - - public double getElevatorVelocity_RotsPerSecond() { - return elevator.getVelocity().getValueAsDouble(); - } - - public double getElevatorPositionInches() { - return getElevatorPositionRots() * ElevatorConstants.kRotationToInches; - } - - public double getElevatorVelocityInchesPerSecond() { - return getElevatorVelocity_RotsPerSecond() * ElevatorConstants.kRotationToInches; - } - - public ElevatorMode getElevatorMode() { - return elevatorMode; - } - - public void changeElevatorOffset(double value) { - elevatorOffset += value; - } - - public void setElevatorStowedMode() { - elevatorMode = ElevatorMode.STOWED; - } - - public void setElevatorStationMode() { - elevatorMode = ElevatorMode.STATION; - } - - public void setElevatorLevelTwoMode() { - elevatorMode = ElevatorMode.LEVEL_TWO; - } - - public void setElevatorLevelThreeMode() { - elevatorMode = ElevatorMode.LEVEL_THREE; - } - - public void setElevatorLevelFourMode() { - elevatorMode = ElevatorMode.LEVEL_FOUR; - } - - public void setElevatorAlgaeLow() { - elevatorMode = ElevatorMode.ALGAE_LOW; - } - - public void setElevatorAlgaeHigh() { - elevatorMode = ElevatorMode.ALGAE_HIGH; - } - - public void setElevatorBarge() { - elevatorMode = ElevatorMode.BARGE; - } - - public void setCoral() { - isCoral = true; - } - - public void setAlgae() { - isCoral = false; - } - - public boolean getIsCoral() { - return isCoral; - } - - public void setAligning(boolean flag) { - isAligning = flag; - } - - public void setZeroing(boolean flag) { - isZeroing = flag; - } - - public void resetAdjust() { - elevatorOffset = 0; - } - - public void setPID() { - - var slot0Configs = talonFXConfigs.Slot0; - slot0Configs.kG = SmartDashboard.getNumber("Elevator kG", ElevatorConstants.kG); - slot0Configs.kS = SmartDashboard.getNumber("Elevator kS", ElevatorConstants.kS); - slot0Configs.kV = SmartDashboard.getNumber("Elevator kV", ElevatorConstants.kV); - slot0Configs.kA = SmartDashboard.getNumber("Elevator kA", ElevatorConstants.kA); - slot0Configs.kP = SmartDashboard.getNumber("Elevator kP", ElevatorConstants.kP); - slot0Configs.kI = SmartDashboard.getNumber("Elevator kI", ElevatorConstants.kI); - slot0Configs.kD = SmartDashboard.getNumber("Elevator kD", ElevatorConstants.kD); - - var motionMagicConfigs = talonFXConfigs.MotionMagic; - motionMagicConfigs.MotionMagicCruiseVelocity = - ElevatorConstants.MM_CRUISE_VELCOCITY_UP; // Target cruise velocity of 80 rps - motionMagicConfigs.MotionMagicAcceleration = - ElevatorConstants.MM_ACCELERATION_UP; // Target acceleration of 160 rps/s (0.5 seconds) - // (not sure if needed - > ) motionMagicConfigs.MotionMagicJerk = 1600; // Target jerk of 1600 rps/s/s (0.1 - // seconds) - - elevator.getConfigurator().refresh(talonFXConfigs); - elevator.getConfigurator().apply(talonFXConfigs); - } -} diff --git a/src/main/java/frc/robot/subsystems/Elevator/Elevator.java b/src/main/java/frc/robot/subsystems/Elevator/Elevator.java new file mode 100644 index 0000000..2fde0f6 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Elevator/Elevator.java @@ -0,0 +1,203 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.Elevator; + +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants.ElevatorConstants; +import frc.robot.util.SmarterDashboard; +import org.littletonrobotics.junction.Logger; + +public class Elevator extends SubsystemBase { + private double elevatorOffset = 0.0; + + private boolean isCoral = false; + private boolean isAligning = false; + private boolean isZeroing = false; + + public static enum ElevatorMode { + STOWED, + STATION, + LEVEL_TWO, + LEVEL_THREE, + LEVEL_FOUR, + ALGAE_LOW, + ALGAE_HIGH, + BARGE, + } + + private ElevatorMode elevatorMode = ElevatorMode.STOWED; + + private ElevatorIO io; + private final ElevatorIOInputsAutoLogged inputs = new ElevatorIOInputsAutoLogged(); + + /** Creates a new Elevator. */ + public Elevator(ElevatorIO io) { + this.io = io; + } + + @Override + public void periodic() { + io.updateInputs(inputs); + Logger.processInputs("Elevator", inputs); + + SmarterDashboard.putNumber("Elevator/Offset", elevatorOffset); + SmarterDashboard.putString("Elevator Mode", elevatorMode.toString()); + SmarterDashboard.putBoolean("Elevator/IsCoral", isCoral); + SmarterDashboard.putNumber("Elevator/Position Inches", getElevatorPositionInches()); + SmarterDashboard.putNumber("Elevator/Velocity (in/sec)", getElevatorVelocityInchesPerSecond()); + SmarterDashboard.putNumber("Elevator/Position Rots", getElevatorPositionRots()); + SmarterDashboard.putNumber("Elevator/Velocity (rot/sec)", getElevatorVelocity_RotsPerSecond()); + + // setAligning(!RobotContainer.align.isAligned()); + } + + public void setElevatorPosition() { + double setpoint = ElevatorConstants.STOWED_ROT + elevatorOffset; + + if (elevatorMode == ElevatorMode.STOWED) { + setpoint = ElevatorConstants.STOWED_ROT + elevatorOffset; + } else if (elevatorMode == ElevatorMode.STATION) { + if (isAligning) { + setpoint = ElevatorConstants.OBSTRUCTED_STATION_ROT + elevatorOffset; + } else { + setpoint = ElevatorConstants.STATION_ROT + elevatorOffset; + } + } + if (isCoral) { + if (elevatorMode == ElevatorMode.LEVEL_TWO) { + setpoint = ElevatorConstants.LEVEL_TWO_ROT + elevatorOffset; + + } else if (elevatorMode == ElevatorMode.LEVEL_THREE) { + setpoint = ElevatorConstants.LEVEL_THREE_ROT + elevatorOffset; + } else if (elevatorMode == ElevatorMode.LEVEL_FOUR) { + if (isAligning) { + // setpoint = RobotContainer.align.getElevatorHeightRots() + elevatorOffset; + // setpoint = ElevatorConstants.BARGE_ROT + elevatorOffset; + setpoint = ElevatorConstants.LEVEL_FOUR_ROT + elevatorOffset; + + } else { + if (DriverStation.isAutonomous()) { + setpoint = ElevatorConstants.LEVEL_FOUR_ROT + elevatorOffset - 0.4; + } else { + setpoint = ElevatorConstants.LEVEL_FOUR_ROT + elevatorOffset; + } + } + } + } else if (!isCoral) { + if (elevatorMode == ElevatorMode.LEVEL_TWO) { + setpoint = ElevatorConstants.ALGAE_LOW_ROT + elevatorOffset; + } else if (elevatorMode == ElevatorMode.LEVEL_THREE) { + setpoint = ElevatorConstants.ALGAE_HIGH_ROT + elevatorOffset; + } else if (elevatorMode == ElevatorMode.LEVEL_FOUR) { + setpoint = ElevatorConstants.BARGE_ROT + elevatorOffset; + } + } + + if (!isZeroing) { + io.reachGoal(setpoint); + } else { + homeElevator(); + } + + SmarterDashboard.putNumber("Elevator/Setpoint", setpoint); + // Logger.recordOutput("Elevator/Align Setpoint", RobotContainer.align.getElevatorHeightRots() + + // elevatorOffset); + } + + public void homeElevator() { + io.setSpeed(0); + } + + public void zeroElevator() { + SmarterDashboard.putNumber("Elevator/New Zero Diff", 0 - inputs.positionRots); + io.setPosition(0); + elevatorOffset = 0; + } + + public void stopElevator() { + io.setSpeed(0); + } + + public double getElevatorPositionRots() { + return inputs.positionRots; + } + + public double getElevatorVelocity_RotsPerSecond() { + return inputs.velocityRps; + } + + public double getElevatorPositionInches() { + return getElevatorPositionRots() * ElevatorConstants.kRotationToInches; + } + + public double getElevatorVelocityInchesPerSecond() { + return getElevatorVelocity_RotsPerSecond() * ElevatorConstants.kRotationToInches; + } + + public ElevatorMode getElevatorMode() { + return elevatorMode; + } + + public void changeElevatorOffset(double value) { + elevatorOffset += value; + } + + public void setElevatorStowedMode() { + elevatorMode = ElevatorMode.STOWED; + } + + public void setElevatorStationMode() { + elevatorMode = ElevatorMode.STATION; + } + + public void setElevatorLevelTwoMode() { + elevatorMode = ElevatorMode.LEVEL_TWO; + } + + public void setElevatorLevelThreeMode() { + elevatorMode = ElevatorMode.LEVEL_THREE; + } + + public void setElevatorLevelFourMode() { + elevatorMode = ElevatorMode.LEVEL_FOUR; + } + + public void setElevatorAlgaeLow() { + elevatorMode = ElevatorMode.ALGAE_LOW; + } + + public void setElevatorAlgaeHigh() { + elevatorMode = ElevatorMode.ALGAE_HIGH; + } + + public void setElevatorBarge() { + elevatorMode = ElevatorMode.BARGE; + } + + public void setCoral() { + isCoral = true; + } + + public void setAlgae() { + isCoral = false; + } + + public boolean getIsCoral() { + return isCoral; + } + + public void setAligning(boolean flag) { + isAligning = flag; + } + + public void setZeroing(boolean flag) { + isZeroing = flag; + } + + public void resetAdjust() { + elevatorOffset = 0; + } +} diff --git a/src/main/java/frc/robot/subsystems/Elevator/ElevatorIO.java b/src/main/java/frc/robot/subsystems/Elevator/ElevatorIO.java new file mode 100644 index 0000000..e927f30 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Elevator/ElevatorIO.java @@ -0,0 +1,24 @@ +package frc.robot.subsystems.Elevator; + +import org.littletonrobotics.junction.AutoLog; + +public interface ElevatorIO { + @AutoLog + public static class ElevatorIOInputs { + public double positionRots = 0.0; + public double velocityRps = 0.0; + + public double appliedVolts = 0.0; + + public double statorCurrent = 0.0; + public double supplyCurrent = 0.0; + } + + public default void updateInputs(ElevatorIOInputs inputs) {} + + public default void reachGoal(double setpoint) {} + + public default void setSpeed(double speed) {} + + public default void setPosition(double position) {} +} diff --git a/src/main/java/frc/robot/subsystems/Elevator/ElevatorIOReal.java b/src/main/java/frc/robot/subsystems/Elevator/ElevatorIOReal.java new file mode 100644 index 0000000..bf8a2e7 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Elevator/ElevatorIOReal.java @@ -0,0 +1,98 @@ +package frc.robot.subsystems.Elevator; + +import com.ctre.phoenix6.BaseStatusSignal; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.Follower; +import com.ctre.phoenix6.controls.MotionMagicVoltage; +import com.ctre.phoenix6.signals.GravityTypeValue; +import frc.lib.drivers.PearadoxTalonFX; +import frc.robot.Constants.ElevatorConstants; + +public class ElevatorIOReal implements ElevatorIO { + private PearadoxTalonFX elevatorMotor; + private PearadoxTalonFX elevatorFollower; + private MotionMagicVoltage motionMagicRequest = new MotionMagicVoltage(0); + private TalonFXConfiguration talonFXConfigs = new TalonFXConfiguration(); + + public ElevatorIOReal() { + elevatorMotor = new PearadoxTalonFX( + ElevatorConstants.ELEVATOR_ID, + ElevatorConstants.MODE, + ElevatorConstants.CURRENT_LIMIT, + ElevatorConstants.IS_INVERTED); + + elevatorFollower = new PearadoxTalonFX( + ElevatorConstants.ELEVATOR_FOLLOWER_ID, + ElevatorConstants.MODE, + ElevatorConstants.CURRENT_LIMIT, + ElevatorConstants.IS_INVERTED); + + var slot0Configs = talonFXConfigs.Slot0; + slot0Configs.kG = ElevatorConstants.kG; // add enough Gravity Gain just before motor starts moving + slot0Configs.kS = ElevatorConstants.kS; // Add 0.1 V output to overcome static friction + slot0Configs.kV = ElevatorConstants.kV; // A velocity target of 1 rps results in 0.1 V output + slot0Configs.kA = ElevatorConstants.kA; // An acceleration of 1 rps/s requires 0.01 V output + slot0Configs.kP = ElevatorConstants.kP; // A position error of 2.5 rotations results in 12 V output, prev 4.8 + slot0Configs.kI = ElevatorConstants.kI; // no output for integrated error + slot0Configs.kD = ElevatorConstants.kD; // A velocity error of 1 rps results in 0.1 V output + + var motionMagicConfigs = talonFXConfigs.MotionMagic; + motionMagicConfigs.MotionMagicCruiseVelocity = + ElevatorConstants.MM_CRUISE_VELCOCITY_UP; // Target cruise velocity of 80 rps + motionMagicConfigs.MotionMagicAcceleration = + ElevatorConstants.MM_ACCELERATION_UP; // Target acceleration of 160 rps/s (0.5 seconds) + // (not sure if needed - > ) motionMagicConfigs.MotionMagicJerk = 1600; // Target jerk of 1600 rps/s/s (0.1 + // seconds) + + talonFXConfigs.SoftwareLimitSwitch.ForwardSoftLimitEnable = true; + talonFXConfigs.SoftwareLimitSwitch.ForwardSoftLimitThreshold = + 33 * ElevatorConstants.GEAR_RATIO / (Math.PI * ElevatorConstants.PULLEY_DIAMETER); + talonFXConfigs.SoftwareLimitSwitch.ReverseSoftLimitEnable = true; + talonFXConfigs.SoftwareLimitSwitch.ReverseSoftLimitThreshold = 0; + talonFXConfigs.Slot0.GravityType = GravityTypeValue.Elevator_Static; + + elevatorMotor.getConfigurator().apply(talonFXConfigs); + + BaseStatusSignal.setUpdateFrequencyForAll( + ElevatorConstants.UPDATE_FREQ, + elevatorMotor.getPosition(), + elevatorMotor.getVelocity(), + elevatorMotor.getDutyCycle(), + elevatorMotor.getMotorVoltage(), + elevatorMotor.getTorqueCurrent(), + elevatorMotor.getSupplyCurrent(), + elevatorMotor.getStatorCurrent()); + + elevatorMotor.optimizeBusUtilization(); + + elevatorFollower.getConfigurator().apply(talonFXConfigs); + elevatorFollower.optimizeBusUtilization(); + elevatorFollower.setControl(new Follower(ElevatorConstants.ELEVATOR_ID, true)); + } + + @Override + public void updateInputs(ElevatorIOInputs inputs) { + inputs.positionRots = elevatorMotor.getPosition().getValueAsDouble(); + inputs.velocityRps = elevatorMotor.getVelocity().getValueAsDouble(); + + inputs.appliedVolts = elevatorMotor.getMotorVoltage().getValueAsDouble(); + + inputs.statorCurrent = elevatorMotor.getStatorCurrent().getValueAsDouble(); + inputs.supplyCurrent = elevatorMotor.getSupplyCurrent().getValueAsDouble(); + } + + @Override + public void reachGoal(double setpoint) { + elevatorMotor.setControl(motionMagicRequest.withPosition(setpoint)); + } + + @Override + public void setSpeed(double speed) { + elevatorMotor.set(speed); + } + + @Override + public void setPosition(double position) { + elevatorMotor.setPosition(position); + } +} diff --git a/src/main/java/frc/robot/subsystems/Elevator/ElevatorIOSim.java b/src/main/java/frc/robot/subsystems/Elevator/ElevatorIOSim.java new file mode 100644 index 0000000..322d269 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Elevator/ElevatorIOSim.java @@ -0,0 +1,118 @@ +package frc.robot.subsystems.Elevator; + +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.MotionMagicVoltage; +import com.ctre.phoenix6.signals.GravityTypeValue; +import com.ctre.phoenix6.sim.TalonFXSimState; +import edu.wpi.first.math.system.plant.DCMotor; +import edu.wpi.first.math.util.Units; +import edu.wpi.first.wpilibj.simulation.ElevatorSim; +import frc.lib.drivers.PearadoxTalonFX; +import frc.robot.Constants.ElevatorConstants; +import frc.robot.Constants.SimulationConstants; + +public class ElevatorIOSim implements ElevatorIO { + private final ElevatorSim elevatorSim = new ElevatorSim( + DCMotor.getKrakenX60(2), + ElevatorConstants.GEAR_RATIO, + SimulationConstants.CARRIAGE_MASS_KG, + SimulationConstants.DRUM_RADIUS_METERS, + SimulationConstants.MIN_HEIGHT, + SimulationConstants.MAX_HEIGHT, + SimulationConstants.SIMULATE_GRAVITY, + SimulationConstants.STARTING_HEIGHT); + + private PearadoxTalonFX elevatorMotor; + private TalonFXSimState elevatorMotorSimState; + private TalonFXConfiguration talonFXConfigs = new TalonFXConfiguration(); + private MotionMagicVoltage motionMagicRequest = new MotionMagicVoltage(0); + + public ElevatorIOSim() { + elevatorMotor = new PearadoxTalonFX( + ElevatorConstants.ELEVATOR_ID, + ElevatorConstants.MODE, + ElevatorConstants.CURRENT_LIMIT, + !ElevatorConstants.IS_INVERTED); + + elevatorMotorSimState = elevatorMotor.getSimState(); + + var slot0Configs = talonFXConfigs.Slot0; + slot0Configs.kG = ElevatorConstants.kG; + slot0Configs.kS = ElevatorConstants.kS; + slot0Configs.kV = ElevatorConstants.kV; + slot0Configs.kA = ElevatorConstants.kA; + slot0Configs.kP = ElevatorConstants.kP; + slot0Configs.kI = ElevatorConstants.kI; + slot0Configs.kD = ElevatorConstants.kD; + + var motionMagicConfigs = talonFXConfigs.MotionMagic; + motionMagicConfigs.MotionMagicCruiseVelocity = + ElevatorConstants.MM_CRUISE_VELCOCITY_UP; // Target cruise velocity of 80 rps + motionMagicConfigs.MotionMagicAcceleration = + ElevatorConstants.MM_ACCELERATION_UP; // Target acceleration of 160 rps/s (0.5 seconds) + // (not sure if needed - > ) motionMagicConfigs.MotionMagicJerk = 1600; // Target jerk of 1600 rps/s/s (0.1 + // seconds) + + talonFXConfigs.SoftwareLimitSwitch.ForwardSoftLimitEnable = true; + talonFXConfigs.SoftwareLimitSwitch.ForwardSoftLimitThreshold = + 33 * ElevatorConstants.GEAR_RATIO / (Math.PI * ElevatorConstants.PULLEY_DIAMETER); + talonFXConfigs.SoftwareLimitSwitch.ReverseSoftLimitEnable = true; + talonFXConfigs.SoftwareLimitSwitch.ReverseSoftLimitThreshold = 0; + talonFXConfigs.Slot0.GravityType = GravityTypeValue.Elevator_Static; + + elevatorMotor.getConfigurator().apply(talonFXConfigs); + } + + @Override + public void updateInputs(ElevatorIOInputs inputs) { + updateSim(); + + inputs.positionRots = elevatorMotor.getPosition().getValueAsDouble(); + inputs.velocityRps = elevatorMotor.getVelocity().getValueAsDouble(); + + inputs.appliedVolts = elevatorMotor.getMotorVoltage().getValueAsDouble(); + + inputs.statorCurrent = elevatorMotor.getStatorCurrent().getValueAsDouble(); + inputs.supplyCurrent = elevatorMotor.getSupplyCurrent().getValueAsDouble(); + } + + @Override + public void reachGoal(double setpoint) { + elevatorMotor.setControl(motionMagicRequest.withPosition(setpoint)); + } + + @Override + public void setSpeed(double speed) { + elevatorMotor.set(speed); + } + + @Override + public void setPosition(double position) { + elevatorMotor.setPosition(position); + } + + private void updateSim() { + elevatorMotorSimState.setSupplyVoltage(12); + + elevatorSim.setInput(elevatorMotorSimState.getMotorVoltage()); + elevatorSim.update(0.02); + + elevatorMotorSimState.setRawRotorPosition(getMotorRotations(elevatorSim.getPositionMeters())); + + // angular velocity = linear velocity / radius + elevatorMotorSimState.setRotorVelocity( + ((elevatorSim.getVelocityMetersPerSecond() / SimulationConstants.DRUM_RADIUS_METERS) + // radians/sec to rotations/sec + / (2.0 * Math.PI)) + * ElevatorConstants.GEAR_RATIO); + + MechVisualizer.getInstance().updateElevatorHeight(elevatorSim.getPositionMeters()); + } + + private static double getMotorRotations(double linearDisplacement) { + // angular displacement in radians = linear displacement / radius + return Units.radiansToRotations(linearDisplacement / SimulationConstants.DRUM_RADIUS_METERS) + // multiply by gear ratio + * ElevatorConstants.GEAR_RATIO; + } +} diff --git a/src/main/java/frc/robot/subsystems/Elevator/MechVisualizer.java b/src/main/java/frc/robot/subsystems/Elevator/MechVisualizer.java new file mode 100644 index 0000000..6ff7450 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Elevator/MechVisualizer.java @@ -0,0 +1,96 @@ +package frc.robot.subsystems.Elevator; + +import edu.wpi.first.math.util.Units; +import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d; +import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d; +import edu.wpi.first.wpilibj.smartdashboard.MechanismRoot2d; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj.util.Color; +import edu.wpi.first.wpilibj.util.Color8Bit; +import frc.robot.Constants.SimulationConstants; + +public class MechVisualizer { + private final double elevatorAngle = 90; // straight up + + private final Mechanism2d mech2d = new Mechanism2d(Units.inchesToMeters(45), Units.inchesToMeters(90)); + private final MechanismRoot2d elevatorRoot = mech2d.getRoot("Elevator Root", Units.inchesToMeters(22.5), 0); + private final MechanismLigament2d elevator2d = + elevatorRoot.append(new MechanismLigament2d("Elevator", SimulationConstants.MIN_HEIGHT, elevatorAngle)); + private MechanismLigament2d arm = elevator2d.append( + new MechanismLigament2d("Arm", Units.inchesToMeters(16.5), 0, 5, new Color8Bit(Color.kYellow))); + + // CAM + // private MechanismLigament2d ee_A = arm.append(new MechanismLigament2d( + // "EE1", SimulationConstants.EE_TO_CORAL_HEIGHT, 0, 3, new Color8Bit(Color.kLightSeaGreen))); + // private MechanismLigament2d ee_B = ee_A.append(new MechanismLigament2d( + // "EE2", SimulationConstants.EE_TO_CORAL_WIDTH, 0, 3, new Color8Bit(Color.kMediumSpringGreen))); + // private MechanismLigament2d coral = ee_B.append( + // new MechanismLigament2d("CORAL", SimulationConstants.CORAL_LENGTH, 0, 2, new + // Color8Bit(Color.kPapayaWhip))); + + private MechanismLigament2d ee23a = arm.append(new MechanismLigament2d( + "EE23a", Units.inchesToMeters(5.6102), 180 - 109.295, 7, new Color8Bit(Color.kDarkSeaGreen))); + private MechanismLigament2d ee34a = ee23a.append(new MechanismLigament2d( + "EE34a", Units.inchesToMeters(2), -(180 - 163.914), 7, new Color8Bit(Color.kMediumSeaGreen))); + private MechanismLigament2d ee45a = ee34a.append(new MechanismLigament2d( + "EE45a", Units.inchesToMeters(5.1181), -(180 - 151.395), 7, new Color8Bit(Color.kLightSeaGreen))); + + private MechanismLigament2d ee23b = arm.append(new MechanismLigament2d( + "EE23b", Units.inchesToMeters(5.6102), 180 + 109.295, 7, new Color8Bit(Color.kDarkBlue))); + private MechanismLigament2d ee34b = ee23b.append(new MechanismLigament2d( + "EE34b", Units.inchesToMeters(2), (180 - 163.914), 7, new Color8Bit(Color.kRoyalBlue))); + private MechanismLigament2d ee45b1 = ee34b.append(new MechanismLigament2d( + "EE45b1", Units.inchesToMeters(5.1181 / 2), (180 - 151.395), 7, new Color8Bit(Color.kDeepSkyBlue))); + private MechanismLigament2d ee45b2 = ee45b1.append( + new MechanismLigament2d("EE45b2", Units.inchesToMeters(5.1181 / 2), 0, 7, new Color8Bit(Color.kSkyBlue))); + + private MechanismLigament2d coral1 = ee45b1.append(new MechanismLigament2d( + "CORAL1", SimulationConstants.CORAL_LENGTH / 2, 90, 10, new Color8Bit(Color.kPapayaWhip))); + private MechanismLigament2d coral2 = ee45b1.append(new MechanismLigament2d( + "CORAL2", SimulationConstants.CORAL_LENGTH / 2, -90, 10, new Color8Bit(Color.kAntiqueWhite))); + + private MechanismLigament2d coral3 = coral2.append(new MechanismLigament2d( + "CORAL3", Units.inchesToMeters(23.4106654653), 180 - 278.855350292, 1, new Color8Bit(Color.kCyan))); + + private MechanismLigament2d coral4 = ee45b1.append(new MechanismLigament2d( + "CORAL4", Units.inchesToMeters(23.249031544), 180 - 354.239159727, 1, new Color8Bit(Color.kRed))); + + // private InterpolatingDoubleTreeMap camLerp = new InterpolatingDoubleTreeMap(); + + private static final MechVisualizer instance = new MechVisualizer(); + + public static MechVisualizer getInstance() { + return instance; + } + + private MechVisualizer() { + // camLerp.put(ArmState.L4.angle, -65.0); + // camLerp.put(ArmState.L3.angle, -55.0); + // camLerp.put(ArmState.L2.angle, -55.0); + // camLerp.put(ArmState.CoralStation.angle, -180 - 35.0); + // camLerp.put(-90.0, -90.0); + } + + public void periodic() { + SmartDashboard.putData("Elevator Sim", mech2d); + } + + public void updateElevatorHeight(double heightMeters) { + // heightMeters += Units.inchesToMeters(39); + elevator2d.setLength(heightMeters); + // ProjectileIntakeSim.getInstance().updateElevatorHeight(heightMeters); + } + + public void updateArmAngle(double angleRads) { + double angleDegs = Units.radiansToDegrees(angleRads); + arm.setAngle(angleDegs - elevatorAngle); + + // double camAngle = camLerp.get(angleDegs); + // ee_A.setAngle(camAngle - angleDegs); // parallel with coral + // ee_B.setAngle(90); // perpendicular to coral + // coral.setAngle(-90); // perpendicular to ee_B + + // ProjectileIntakeSim.getInstance().updateArmAngle(angleRads); + // ProjectileIntakeSim.getInstance().updateCamAngle(Units.degreesToRadians(camAngle)); + } +} From cde5d1d952722771557c676a13d7493d40dc7383 Mon Sep 17 00:00:00 2001 From: nh17000 <46301909+nh17000@users.noreply.github.com> Date: Sat, 3 May 2025 15:31:46 -0500 Subject: [PATCH 02/58] Simulate Arm --- simgui-ds.json | 2 +- simgui-window.json | 14 +- simgui.json | 7 +- src/main/java/frc/robot/Constants.java | 15 +- src/main/java/frc/robot/RobotContainer.java | 12 +- src/main/java/frc/robot/commands/ArmHold.java | 8 +- src/main/java/frc/robot/subsystems/Arm.java | 268 ------------------ .../java/frc/robot/subsystems/Arm/Arm.java | 169 +++++++++++ .../java/frc/robot/subsystems/Arm/ArmIO.java | 20 ++ .../frc/robot/subsystems/Arm/ArmIOReal.java | 68 +++++ .../frc/robot/subsystems/Arm/ArmIOSim.java | 105 +++++++ .../java/frc/robot/subsystems/Climber.java | 2 - .../subsystems/Elevator/MechVisualizer.java | 2 +- .../frc/robot/subsystems/EndEffector.java | 17 +- 14 files changed, 399 insertions(+), 310 deletions(-) delete mode 100644 src/main/java/frc/robot/subsystems/Arm.java create mode 100644 src/main/java/frc/robot/subsystems/Arm/Arm.java create mode 100644 src/main/java/frc/robot/subsystems/Arm/ArmIO.java create mode 100644 src/main/java/frc/robot/subsystems/Arm/ArmIOReal.java create mode 100644 src/main/java/frc/robot/subsystems/Arm/ArmIOSim.java diff --git a/simgui-ds.json b/simgui-ds.json index 9f898d1..a8c42be 100644 --- a/simgui-ds.json +++ b/simgui-ds.json @@ -82,7 +82,7 @@ 47, -1, -1, - -1, + 39, 267 ], "povConfig": [ diff --git a/simgui-window.json b/simgui-window.json index 52b5d5d..05c68f4 100644 --- a/simgui-window.json +++ b/simgui-window.json @@ -27,7 +27,7 @@ "###/SmartDashboard/Auto Mode": { "Collapsed": "0", "Pos": "162,101", - "Size": "363,62" + "Size": "361,66" }, "###/SmartDashboard/Elevator Sim": { "Collapsed": "0", @@ -47,12 +47,12 @@ "###FMS": { "Collapsed": "0", "Pos": "8,699", - "Size": "233,258" + "Size": "235,244" }, "###Joysticks": { "Collapsed": "0", "Pos": "292,408", - "Size": "1156,291" + "Size": "1156,271" }, "###Keyboard 0 Settings": { "Collapsed": "0", @@ -61,7 +61,7 @@ }, "###Keyboard 1 Settings": { "Collapsed": "0", - "Pos": "1299,27", + "Pos": "1299,26", "Size": "300,560" }, "###NetworkTables": { @@ -87,12 +87,12 @@ "###System Joysticks": { "Collapsed": "0", "Pos": "0,399", - "Size": "273,308" + "Size": "273,290" }, "###Timing": { "Collapsed": "0", "Pos": "1,180", - "Size": "199,213" + "Size": "197,215" }, "Debug##Default": { "Collapsed": "0", @@ -102,7 +102,7 @@ "Robot State": { "Collapsed": "0", "Pos": "5,20", - "Size": "143,158" + "Size": "137,152" } } } diff --git a/simgui.json b/simgui.json index 1ad037b..399047e 100644 --- a/simgui.json +++ b/simgui.json @@ -46,11 +46,11 @@ }, "transitory": { "AdvantageKit": { - "Elevator": { + "Arm": { "open": true }, "RealOutputs": { - "Elevator": { + "Arm": { "open": true }, "open": true @@ -59,6 +59,9 @@ } } }, + "NetworkTables Info": { + "visible": true + }, "Plot": { "Plot <0>": { "plots": [ diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index dbfc467..9365ef2 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -211,10 +211,10 @@ public static final class ArmConstants { public static final double UPDATE_FREQ = 50; public static final double kG = 0.0; // 0.35; - public static final double kS = 0.0; // 0.15; - public static final double kV = 0.0; // 0.2 + public static final double kS = 0.15; // 0.15; + public static final double kV = 7.2; // 0.2 public static final double kA = 0.0; // 0.07 - public static final double kP = 0.0; // 0.3 + public static final double kP = 0.4; // 0.3 public static final double kI = 0.0; public static final double kD = 0.0; // 0.05 @@ -292,13 +292,12 @@ public static final class LEDConstants { public static class SimulationConstants { public static final boolean SIMULATE_GRAVITY = true; - public static final double ARM_GEARING = 15; - public static final double ARM_MASS = Units.lbsToKilograms(4); + public static final double ARM_MASS = Units.lbsToKilograms(8); public static final double ARM_LENGTH = Units.inchesToMeters(12); public static final double ARM_MOI = SingleJointedArmSim.estimateMOI(ARM_LENGTH, ARM_MASS); - public static final double MIN_ANGLE = Units.degreesToRadians(-180); - public static final double MAX_ANGLE = Units.degreesToRadians(180); - public static final double STARTING_ANGLE = Units.degreesToRadians(-90); + public static final double MIN_ANGLE = Double.NEGATIVE_INFINITY; + public static final double MAX_ANGLE = Double.POSITIVE_INFINITY; + public static final double STARTING_ANGLE = Units.degreesToRadians(-96); // joint of ee to bottom of coral public static final double CAM_LENGTH = Units.inchesToMeters(14.5); diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 52dd501..5446524 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -27,8 +27,10 @@ import frc.robot.commands.AutoAlign; import frc.robot.commands.ElevatorHold; import frc.robot.generated.TunerConstants; -import frc.robot.subsystems.Arm; -import frc.robot.subsystems.Arm.ArmMode; +import frc.robot.subsystems.Arm.Arm; +import frc.robot.subsystems.Arm.Arm.ArmMode; +import frc.robot.subsystems.Arm.ArmIOReal; +import frc.robot.subsystems.Arm.ArmIOSim; import frc.robot.subsystems.Climber; import frc.robot.subsystems.CommandSwerveDrivetrain; import frc.robot.subsystems.Elevator.Elevator; @@ -42,7 +44,7 @@ public class RobotContainer { private double MaxAngularRate = RotationsPerSecond.of(0.75).in(RadiansPerSecond); private Elevator elevator; - public static final Arm arm = Arm.getInstance(); + private Arm arm; public static final EndEffector endEffector = EndEffector.getInstance(); public static final Climber climber = Climber.getInstance(); public static final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain(); @@ -110,8 +112,10 @@ public class RobotContainer { public RobotContainer() { if (Robot.isReal()) { elevator = new Elevator(new ElevatorIOReal()); + arm = new Arm(new ArmIOReal()); } else { elevator = new Elevator(new ElevatorIOSim()); + arm = new Arm(new ArmIOSim()); } setDefaultCommands(); @@ -437,7 +441,7 @@ public void setDefaultCommands() { .withRotationalRate(drivetrain.turnLimiter.calculate(-driverController.getRightX()) * MaxAngularRate))); elevator.setDefaultCommand(new ElevatorHold(elevator)); - arm.setDefaultCommand(new ArmHold()); + arm.setDefaultCommand(new ArmHold(arm)); // climber.setDefaultCommand(new ClimbCommand()); // ledstrip.setDefaultCommand(ledstrip.defaultCommand(() -> endEffector.isCoral())); } diff --git a/src/main/java/frc/robot/commands/ArmHold.java b/src/main/java/frc/robot/commands/ArmHold.java index 05ef2d9..082236a 100644 --- a/src/main/java/frc/robot/commands/ArmHold.java +++ b/src/main/java/frc/robot/commands/ArmHold.java @@ -1,13 +1,13 @@ package frc.robot.commands; import edu.wpi.first.wpilibj2.command.Command; -import frc.robot.subsystems.Arm; +import frc.robot.subsystems.Arm.Arm; public class ArmHold extends Command { + private Arm arm; - private Arm arm = Arm.getInstance(); - - public ArmHold() { + public ArmHold(Arm arm) { + this.arm = arm; addRequirements(arm); } diff --git a/src/main/java/frc/robot/subsystems/Arm.java b/src/main/java/frc/robot/subsystems/Arm.java deleted file mode 100644 index 9dad099..0000000 --- a/src/main/java/frc/robot/subsystems/Arm.java +++ /dev/null @@ -1,268 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package frc.robot.subsystems; - -import static edu.wpi.first.units.Units.*; - -import com.ctre.phoenix6.BaseStatusSignal; -import com.ctre.phoenix6.SignalLogger; -import com.ctre.phoenix6.configs.TalonFXConfiguration; -import com.ctre.phoenix6.controls.MotionMagicVoltage; -import com.ctre.phoenix6.controls.PositionVoltage; -import com.ctre.phoenix6.controls.VoltageOut; -import com.ctre.phoenix6.signals.GravityTypeValue; -import com.ctre.phoenix6.signals.NeutralModeValue; -import edu.wpi.first.math.util.Units; -import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.SubsystemBase; -import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; -import frc.lib.drivers.PearadoxTalonFX; -import frc.robot.Constants.ArmConstants; -import frc.robot.util.SmarterDashboard; - -public class Arm extends SubsystemBase { - private PearadoxTalonFX pivot; - private MotionMagicVoltage motionMagicRequest = new MotionMagicVoltage(0); - - private ArmMode armMode = ArmMode.Stowed; - private TalonFXConfiguration talonFXConfigs; - - private VoltageOut voltageRequest = new VoltageOut(0); - - private boolean isCoral = true; - private boolean isAligning = false; - private double lastAngle = 0; - - public enum ArmMode { - Intake, - L2, - L3, - L4, - Stowed, - LOLLICLIMB - } - - private double armAdjust = 0.0; - - public static final Arm arm = new Arm(); - - public static Arm getInstance() { - return arm; - } - - private final VoltageOut m_voltReq = new VoltageOut(0.0); - - private final SysIdRoutine m_sysIdRoutineTranslation = new SysIdRoutine( - new SysIdRoutine.Config( - null, // Use default ramp rate (1 V/s) - Volts.of(4), // Reduce dynamic step voltage to 4 V to prevent brownout - null, // Use default timeout (10 s) - // Log state with SignalLogger class - state -> SignalLogger.writeString("SysIdTranslation_State", state.toString())), - new SysIdRoutine.Mechanism((volts) -> pivot.setControl(m_voltReq.withOutput(volts.in(Volts))), null, this)); - - public Command sysIdQuasistatic(SysIdRoutine.Direction direction) { - return m_sysIdRoutineTranslation.quasistatic(direction); - } - - public Command sysIdDynamic(SysIdRoutine.Direction direction) { - return m_sysIdRoutineTranslation.dynamic(direction); - } - - public Arm() { - pivot = new PearadoxTalonFX( - ArmConstants.ARM_KRAKEN_ID, - NeutralModeValue.Brake, - ArmConstants.CURRENT_LIMIT, - ArmConstants.CURRENT_LIMIT, - false); - - BaseStatusSignal.setUpdateFrequencyForAll( - ArmConstants.UPDATE_FREQ, - pivot.getPosition(), - pivot.getVelocity(), - pivot.getDutyCycle(), - pivot.getMotorVoltage(), - pivot.getTorqueCurrent(), - pivot.getSupplyCurrent(), - pivot.getStatorCurrent()); - - pivot.optimizeBusUtilization(); - - talonFXConfigs = new TalonFXConfiguration(); - - talonFXConfigs.Voltage.PeakForwardVoltage = 4.5; - talonFXConfigs.Voltage.PeakReverseVoltage = -4.5; - - var slot0Configs = talonFXConfigs.Slot0; - slot0Configs.kG = 0; // add enough Gravity Gain just before motor starts moving - slot0Configs.kS = 0.15; // Add x output to overcome static friction - slot0Configs.kV = 7.2; // A velocity target of 1 rps results in x output - slot0Configs.kA = 0; // An acceleration of 1 rps/s requires x output - slot0Configs.kP = 0.4; // A position error of x rotations results in 12 V output - slot0Configs.kI = 0; // no output for integrated error - slot0Configs.kD = 0; // A velocity error of 1 rps results in x output - slot0Configs.GravityType = GravityTypeValue.Arm_Cosine; - - var slot1Configs = talonFXConfigs.Slot1; // configs for game piece - slot1Configs.kG = 0; - slot1Configs.kS = 0; - slot1Configs.kV = 0; - slot1Configs.kA = 0; - slot1Configs.kP = 0; - slot1Configs.kI = 0; - slot1Configs.kD = 0; - - var motionMagicConfigs = talonFXConfigs.MotionMagic; - motionMagicConfigs.MotionMagicCruiseVelocity = ArmConstants.MM_MAX_CRUISE_VELOCITY; - motionMagicConfigs.MotionMagicAcceleration = ArmConstants.MM_MAX_CRUISE_ACCELERATION; - - pivot.getConfigurator().apply(talonFXConfigs); - } - - @Override - public void periodic() { - SmarterDashboard.putNumber("Arm/Raw Position", pivot.getPosition().getValueAsDouble()); - SmarterDashboard.putNumber("Arm/Angle degrees", getArmAngleDegrees()); - SmarterDashboard.putNumber("Arm/Velocity rot/sec", pivot.getVelocity().getValueAsDouble()); - SmarterDashboard.putNumber("Arm/Voltage", pivot.getMotorVoltage().getValueAsDouble()); - SmarterDashboard.putNumber( - "Arm/Supply Current", pivot.getSupplyCurrent().getValueAsDouble()); - SmarterDashboard.putNumber( - "Arm/Stator Current", pivot.getStatorCurrent().getValueAsDouble()); - SmarterDashboard.putNumber("Arm/Adjust", armAdjust); - SmarterDashboard.putString("Arm/Mode", armMode.toString()); - SmarterDashboard.putBoolean("Arm/IsCoral", isCoral); - SmarterDashboard.putNumber("Arm/DeltaAngle", deltaArmAngle()); - SmarterDashboard.putNumber("Arm/kG", 0.35 * Math.cos(-1 * Units.degreesToRadians(getArmAngleDegrees() - 96))); - - // setAligning(!RobotContainer.align.isAligned()); - } - - public void armHold() { - double setpoint = ArmConstants.ARM_STOWED_ROT + armAdjust; - - if (isCoral) { - if (armMode == ArmMode.Stowed) { - setpoint = ArmConstants.ARM_STOWED_ROT + armAdjust; - } else if (armMode == ArmMode.Intake) { - if (isAligning) { - setpoint = ArmConstants.ARM_STATION_BEHIND_CORAL + armAdjust; - - } else { - setpoint = ArmConstants.ARM_INTAKE_ROT + armAdjust; - } - } else if (armMode == ArmMode.L2) { - setpoint = ArmConstants.ARM_LEVEL_2_ROT + armAdjust; - } else if (armMode == ArmMode.L3) { - setpoint = ArmConstants.ARM_LEVEL_3_ROT + armAdjust; - } else if (armMode == ArmMode.L4) { - if (isAligning) { - // setpoint = RobotContainer.align.getArmAngleRots() + armAdjust; - setpoint = ArmConstants.ARM_L4_BEHIND_CORAL + armAdjust; - - } else { - setpoint = ArmConstants.ARM_LEVEL_4_ROT + armAdjust; - } - } - } else if (!isCoral) { - if (armMode == ArmMode.Stowed) { - setpoint = ArmConstants.ARM_LOLLIPOP + armAdjust; - } else if (armMode == ArmMode.L2) { - setpoint = ArmConstants.ARM_ALGAE_LOW + armAdjust; - } else if (armMode == ArmMode.L3) { - setpoint = ArmConstants.ARM_ALGAE_HIGH + armAdjust; - } else if (armMode == ArmMode.L4) { - setpoint = ArmConstants.ARM_BARGE + armAdjust; - } - } - - // Logger.recordOutput("Arm/Align Setpoint", RobotContainer.align.getArmAngleRots() + armAdjust); - - // pivot.setControl(motionMagicRequest.withPosition(setpoint)); - pivot.setControl(new PositionVoltage(-setpoint) - .withFeedForward(0.35 * Math.cos(-1 * Units.degreesToRadians(getArmAngleDegrees() - 96)))); - // pivot.setControl(new PositionVoltage(-setpoint).withFeedForward(ArmConstants.kG * - // Math.cos(getArmAngleDegrees() - 96))); - SmarterDashboard.putNumber("Arm/Cur Setpoint", -setpoint); - } - - public double deltaArmAngle() { - var temp = lastAngle; - lastAngle = getArmAngleDegrees(); - return lastAngle - temp; - } - - public void setArmIntake() { - armMode = ArmMode.Intake; - } - - public void setArmL2() { - armMode = ArmMode.L2; - } - - public void setArmL3() { - armMode = ArmMode.L3; - } - - public void setArmL4() { - armMode = ArmMode.L4; - } - - public void setStowed() { - armMode = ArmMode.Stowed; - } - - public void setLollipopOrClimb() { - armMode = ArmMode.LOLLICLIMB; - } - - public void setCoral() { - isCoral = true; - } - - public void setAlgae() { - isCoral = false; - } - - public ArmMode getArmMode() { - return armMode; - } - - public boolean getIsCoral() { - return isCoral; - } - - public void setAligning(boolean flag) { - isAligning = flag; - } - - public double getPivotPosition() { - return pivot.getPosition().getValueAsDouble() / ArmConstants.ARM_GEAR_RATIO; - } - - public double getArmAngleDegrees() { - return Units.rotationsToDegrees(getPivotPosition()); - } - - // public void zeroArm() { - // pivot.setPosition(ArmConstants.ARM_STOWED_ROT * ArmConstants.ARM_GEAR_RATIO); - // } - - public void armAdjust(double adjustBy) { - armAdjust += adjustBy; - } - - public void resetAdjust() { - armAdjust = 0; - } - - // public double getAutoArmAngle(){ - // double dist = RobotContainer.align.getTagDist(); //this doesnt work maybe make AutoAlign a subsystem - - // return Math.acos((dist + ArmConstants.ARM_LENGTH * Math.cos(0)) / ArmConstants.ARM_LENGTH); //TODO Current - // Angle Setpoint - // } -} diff --git a/src/main/java/frc/robot/subsystems/Arm/Arm.java b/src/main/java/frc/robot/subsystems/Arm/Arm.java new file mode 100644 index 0000000..6dad98a --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Arm/Arm.java @@ -0,0 +1,169 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.Arm; + +import edu.wpi.first.math.util.Units; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants.ArmConstants; +import frc.robot.util.SmarterDashboard; +import org.littletonrobotics.junction.Logger; + +public class Arm extends SubsystemBase { + private boolean isCoral = true; + private boolean isAligning = false; + private double lastAngle = 0.0; + private double armAdjust = 0.0; + + public enum ArmMode { + Intake, + L2, + L3, + L4, + Stowed, + LOLLICLIMB + } + + private static ArmMode armMode = ArmMode.Stowed; + + private ArmIO io; + private final ArmIOInputsAutoLogged inputs = new ArmIOInputsAutoLogged(); + + public Arm(ArmIO io) { + this.io = io; + } + + @Override + public void periodic() { + io.updateInputs(inputs); + Logger.processInputs("Arm", inputs); + + SmarterDashboard.putNumber("Arm/Angle degrees", getArmAngleDegrees()); + SmarterDashboard.putNumber("Arm/Adjust", armAdjust); + SmarterDashboard.putString("Arm/Mode", armMode.toString()); + SmarterDashboard.putBoolean("Arm/IsCoral", isCoral); + SmarterDashboard.putNumber("Arm/DeltaAngle", deltaArmAngle()); + SmarterDashboard.putNumber("Arm/kG", 0.35 * Math.cos(-1 * Units.degreesToRadians(getArmAngleDegrees() - 96))); + + // setAligning(!RobotContainer.align.isAligned()); + } + + public void armHold() { + double setpoint = ArmConstants.ARM_STOWED_ROT + armAdjust; + + if (isCoral) { + if (armMode == ArmMode.Stowed) { + setpoint = ArmConstants.ARM_STOWED_ROT + armAdjust; + } else if (armMode == ArmMode.Intake) { + if (isAligning) { + setpoint = ArmConstants.ARM_STATION_BEHIND_CORAL + armAdjust; + + } else { + setpoint = ArmConstants.ARM_INTAKE_ROT + armAdjust; + } + } else if (armMode == ArmMode.L2) { + setpoint = ArmConstants.ARM_LEVEL_2_ROT + armAdjust; + } else if (armMode == ArmMode.L3) { + setpoint = ArmConstants.ARM_LEVEL_3_ROT + armAdjust; + } else if (armMode == ArmMode.L4) { + if (isAligning) { + // setpoint = RobotContainer.align.getArmAngleRots() + armAdjust; + setpoint = ArmConstants.ARM_L4_BEHIND_CORAL + armAdjust; + + } else { + setpoint = ArmConstants.ARM_LEVEL_4_ROT + armAdjust; + } + } + } else if (!isCoral) { + if (armMode == ArmMode.Stowed) { + setpoint = ArmConstants.ARM_LOLLIPOP + armAdjust; + } else if (armMode == ArmMode.L2) { + setpoint = ArmConstants.ARM_ALGAE_LOW + armAdjust; + } else if (armMode == ArmMode.L3) { + setpoint = ArmConstants.ARM_ALGAE_HIGH + armAdjust; + } else if (armMode == ArmMode.L4) { + setpoint = ArmConstants.ARM_BARGE + armAdjust; + } + } + + // Logger.recordOutput("Arm/Align Setpoint", RobotContainer.align.getArmAngleRots() + armAdjust); + + // pivot.setControl(motionMagicRequest.withPosition(setpoint)); + io.runPosition(-setpoint, getFeedforwardVolts()); + + // pivot.setControl(new PositionVoltage(-setpoint).withFeedForward(ArmConstants.kG * + // Math.cos(getArmAngleDegrees() - 96))); + SmarterDashboard.putNumber("Arm/Cur Setpoint", -setpoint); + } + + public double deltaArmAngle() { + var temp = lastAngle; + lastAngle = getArmAngleDegrees(); + return lastAngle - temp; + } + + public void setArmIntake() { + armMode = ArmMode.Intake; + } + + public void setArmL2() { + armMode = ArmMode.L2; + } + + public void setArmL3() { + armMode = ArmMode.L3; + } + + public void setArmL4() { + armMode = ArmMode.L4; + } + + public void setStowed() { + armMode = ArmMode.Stowed; + } + + public void setLollipopOrClimb() { + armMode = ArmMode.LOLLICLIMB; + } + + public void setCoral() { + isCoral = true; + } + + public void setAlgae() { + isCoral = false; + } + + public static ArmMode getArmMode() { + return armMode; + } + + public boolean getIsCoral() { + return isCoral; + } + + public void setAligning(boolean flag) { + isAligning = flag; + } + + public double getPivotPosition() { + return inputs.positionRots / ArmConstants.ARM_GEAR_RATIO; + } + + public double getArmAngleDegrees() { + return Units.rotationsToDegrees(getPivotPosition()); + } + + public double getFeedforwardVolts() { + return 0.35 * Math.cos(-1 * Units.degreesToRadians(getArmAngleDegrees() - 96)); + } + + public void armAdjust(double adjustBy) { + armAdjust += adjustBy; + } + + public void resetAdjust() { + armAdjust = 0; + } +} diff --git a/src/main/java/frc/robot/subsystems/Arm/ArmIO.java b/src/main/java/frc/robot/subsystems/Arm/ArmIO.java new file mode 100644 index 0000000..1616e32 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Arm/ArmIO.java @@ -0,0 +1,20 @@ +package frc.robot.subsystems.Arm; + +import org.littletonrobotics.junction.AutoLog; + +public interface ArmIO { + @AutoLog + public static class ArmIOInputs { + public double positionRots = 0.0; + public double velocityRps = 0.0; + + public double appliedVolts = 0.0; + + public double statorCurrent = 0.0; + public double supplyCurrent = 0.0; + } + + public default void updateInputs(ArmIOInputsAutoLogged inputs) {} + + public default void runPosition(double setpoint, double feedforward) {} +} diff --git a/src/main/java/frc/robot/subsystems/Arm/ArmIOReal.java b/src/main/java/frc/robot/subsystems/Arm/ArmIOReal.java new file mode 100644 index 0000000..2081063 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Arm/ArmIOReal.java @@ -0,0 +1,68 @@ +package frc.robot.subsystems.Arm; + +import com.ctre.phoenix6.BaseStatusSignal; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.PositionVoltage; +import com.ctre.phoenix6.signals.GravityTypeValue; +import com.ctre.phoenix6.signals.NeutralModeValue; +import frc.lib.drivers.PearadoxTalonFX; +import frc.robot.Constants.ArmConstants; + +public class ArmIOReal implements ArmIO { + private PearadoxTalonFX pivot; + private TalonFXConfiguration talonFXConfigs; + + public ArmIOReal() { + pivot = new PearadoxTalonFX( + ArmConstants.ARM_KRAKEN_ID, + NeutralModeValue.Brake, + ArmConstants.CURRENT_LIMIT, + ArmConstants.CURRENT_LIMIT, + false); + + BaseStatusSignal.setUpdateFrequencyForAll( + ArmConstants.UPDATE_FREQ, + pivot.getPosition(), + pivot.getVelocity(), + pivot.getDutyCycle(), + pivot.getMotorVoltage(), + pivot.getTorqueCurrent(), + pivot.getSupplyCurrent(), + pivot.getStatorCurrent()); + + pivot.optimizeBusUtilization(); + + talonFXConfigs = new TalonFXConfiguration(); + + talonFXConfigs.Voltage.PeakForwardVoltage = 4.5; + talonFXConfigs.Voltage.PeakReverseVoltage = -4.5; + + var slot0Configs = talonFXConfigs.Slot0; + slot0Configs.kG = 0; // add enough Gravity Gain just before motor starts moving + slot0Configs.kS = 0.15; // Add x output to overcome static friction + slot0Configs.kV = 7.2; // A velocity target of 1 rps results in x output + slot0Configs.kA = 0; // An acceleration of 1 rps/s requires x output + slot0Configs.kP = 0.4; // A position error of x rotations results in 12 V output + slot0Configs.kI = 0; // no output for integrated error + slot0Configs.kD = 0; // A velocity error of 1 rps results in x output + slot0Configs.GravityType = GravityTypeValue.Arm_Cosine; + + pivot.getConfigurator().apply(talonFXConfigs); + } + + @Override + public void updateInputs(ArmIOInputsAutoLogged inputs) { + inputs.positionRots = pivot.getPosition().getValueAsDouble(); + inputs.velocityRps = pivot.getVelocity().getValueAsDouble(); + + inputs.appliedVolts = pivot.getMotorVoltage().getValueAsDouble(); + + inputs.statorCurrent = pivot.getStatorCurrent().getValueAsDouble(); + inputs.supplyCurrent = pivot.getSupplyCurrent().getValueAsDouble(); + } + + @Override + public void runPosition(double setpoint, double feedforward) { + pivot.setControl(new PositionVoltage(setpoint).withFeedForward(feedforward)); + } +} diff --git a/src/main/java/frc/robot/subsystems/Arm/ArmIOSim.java b/src/main/java/frc/robot/subsystems/Arm/ArmIOSim.java new file mode 100644 index 0000000..e051e64 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/Arm/ArmIOSim.java @@ -0,0 +1,105 @@ +package frc.robot.subsystems.Arm; + +import com.ctre.phoenix6.BaseStatusSignal; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.controls.PositionVoltage; +import com.ctre.phoenix6.signals.GravityTypeValue; +import com.ctre.phoenix6.signals.NeutralModeValue; +import com.ctre.phoenix6.sim.TalonFXSimState; +import edu.wpi.first.math.system.plant.DCMotor; +import edu.wpi.first.math.util.Units; +import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; +import frc.lib.drivers.PearadoxTalonFX; +import frc.robot.Constants.ArmConstants; +import frc.robot.Constants.SimulationConstants; +import frc.robot.subsystems.Elevator.MechVisualizer; + +public class ArmIOSim implements ArmIO { + private SingleJointedArmSim armSim = new SingleJointedArmSim( + DCMotor.getKrakenX60(1), + ArmConstants.ARM_GEAR_RATIO, + SimulationConstants.ARM_MOI, + SimulationConstants.ARM_LENGTH, + SimulationConstants.MIN_ANGLE, + SimulationConstants.MAX_ANGLE, + SimulationConstants.SIMULATE_GRAVITY, + SimulationConstants.STARTING_ANGLE); + + private PearadoxTalonFX pivot; + private TalonFXConfiguration talonFXConfigs; + private TalonFXSimState pivotMotorSimState; + + public ArmIOSim() { + pivot = new PearadoxTalonFX( + ArmConstants.ARM_KRAKEN_ID, + NeutralModeValue.Brake, + ArmConstants.CURRENT_LIMIT, + ArmConstants.CURRENT_LIMIT, + false); + + BaseStatusSignal.setUpdateFrequencyForAll( + ArmConstants.UPDATE_FREQ, + pivot.getPosition(), + pivot.getVelocity(), + pivot.getDutyCycle(), + pivot.getMotorVoltage(), + pivot.getTorqueCurrent(), + pivot.getSupplyCurrent(), + pivot.getStatorCurrent()); + + pivot.optimizeBusUtilization(); + + talonFXConfigs = new TalonFXConfiguration(); + + talonFXConfigs.Voltage.PeakForwardVoltage = 4.5; + talonFXConfigs.Voltage.PeakReverseVoltage = -4.5; + + var slot0Configs = talonFXConfigs.Slot0; + slot0Configs.kG = 0; // add enough Gravity Gain just before motor starts moving + slot0Configs.kS = 0.15; // Add x output to overcome static friction + slot0Configs.kV = 7.2; // A velocity target of 1 rps results in x output + slot0Configs.kA = 0; // An acceleration of 1 rps/s requires x output + slot0Configs.kP = 0.4; // A position error of x rotations results in 12 V output + slot0Configs.kI = 0; // no output for integrated error + slot0Configs.kD = 0; // A velocity error of 1 rps results in x output + slot0Configs.GravityType = GravityTypeValue.Arm_Cosine; + + pivot.getConfigurator().apply(talonFXConfigs); + + pivotMotorSimState = pivot.getSimState(); + } + + @Override + public void updateInputs(ArmIOInputsAutoLogged inputs) { + updateSim(); + + inputs.positionRots = pivot.getPosition().getValueAsDouble(); + inputs.velocityRps = pivot.getVelocity().getValueAsDouble(); + + inputs.appliedVolts = pivot.getMotorVoltage().getValueAsDouble(); + + inputs.statorCurrent = pivot.getStatorCurrent().getValueAsDouble(); + inputs.supplyCurrent = pivot.getSupplyCurrent().getValueAsDouble(); + } + + @Override + public void runPosition(double setpoint, double feedforward) { + pivot.setControl(new PositionVoltage(-setpoint).withFeedForward(feedforward)); + } + + private void updateSim() { + pivotMotorSimState.setSupplyVoltage(12); + + armSim.setInputVoltage(pivotMotorSimState.getMotorVoltage()); + armSim.update(0.02); + + pivotMotorSimState.setRawRotorPosition( + (Units.radiansToRotations(armSim.getAngleRads() - SimulationConstants.STARTING_ANGLE)) + * ArmConstants.ARM_GEAR_RATIO); + + pivotMotorSimState.setRotorVelocity( + Units.radiansToRotations(armSim.getVelocityRadPerSec() * ArmConstants.ARM_GEAR_RATIO)); + + MechVisualizer.getInstance().updateArmAngle(armSim.getAngleRads()); + } +} diff --git a/src/main/java/frc/robot/subsystems/Climber.java b/src/main/java/frc/robot/subsystems/Climber.java index df043e7..918ed2f 100644 --- a/src/main/java/frc/robot/subsystems/Climber.java +++ b/src/main/java/frc/robot/subsystems/Climber.java @@ -19,8 +19,6 @@ public class Climber extends SubsystemBase { private static final Climber CLIMBER = new Climber(); private TalonFXConfiguration talonFXConfigs; - private static final Arm ARM = Arm.getInstance(); - private double setpoint = ClimbConstants.CLIMB_SETPOINT; private double climberOffset = 0; diff --git a/src/main/java/frc/robot/subsystems/Elevator/MechVisualizer.java b/src/main/java/frc/robot/subsystems/Elevator/MechVisualizer.java index 6ff7450..a772578 100644 --- a/src/main/java/frc/robot/subsystems/Elevator/MechVisualizer.java +++ b/src/main/java/frc/robot/subsystems/Elevator/MechVisualizer.java @@ -76,7 +76,7 @@ public void periodic() { } public void updateElevatorHeight(double heightMeters) { - // heightMeters += Units.inchesToMeters(39); + heightMeters += Units.inchesToMeters(39); elevator2d.setLength(heightMeters); // ProjectileIntakeSim.getInstance().updateElevatorHeight(heightMeters); } diff --git a/src/main/java/frc/robot/subsystems/EndEffector.java b/src/main/java/frc/robot/subsystems/EndEffector.java index 8376b16..de8ed04 100644 --- a/src/main/java/frc/robot/subsystems/EndEffector.java +++ b/src/main/java/frc/robot/subsystems/EndEffector.java @@ -6,7 +6,6 @@ import com.ctre.phoenix6.BaseStatusSignal; import com.ctre.phoenix6.configs.Slot0Configs; -import com.ctre.phoenix6.controls.PositionVoltage; import com.ctre.phoenix6.signals.NeutralModeValue; import edu.wpi.first.math.filter.Debouncer; import edu.wpi.first.math.filter.Debouncer.DebounceType; @@ -17,7 +16,8 @@ import frc.robot.Constants.ArmConstants; import frc.robot.Constants.EndEffectorConstants; import frc.robot.RobotContainer; -import frc.robot.subsystems.Arm.ArmMode; +import frc.robot.subsystems.Arm.Arm; +import frc.robot.subsystems.Arm.Arm.ArmMode; import frc.robot.util.SmarterDashboard; public class EndEffector extends SubsystemBase { @@ -26,8 +26,6 @@ public class EndEffector extends SubsystemBase { private static final LEDStrip leds = LEDStrip.getInstance(); - private static final Arm ARM = Arm.getInstance(); - public static EndEffector getInstance() { return END_EFFECTOR; } @@ -175,9 +173,9 @@ public void algaeOut() { // intakes public void coralOut() { - if (ARM.getArmMode() == ArmMode.L2 || ARM.getArmMode() == ArmMode.Stowed) { + if (Arm.getArmMode() == ArmMode.L2 || Arm.getArmMode() == ArmMode.Stowed) { endEffector.set(0.1); - } else if (ARM.getArmMode() == ArmMode.L3) { + } else if (Arm.getArmMode() == ArmMode.L3) { endEffector.set(0.3); } else endEffector.set(EndEffectorConstants.PUSH_SPEED); setLastRot(); @@ -207,13 +205,6 @@ public void stop() { endEffector.set(0); } - public void passiveCoral() { - PositionVoltage request = new PositionVoltage(0).withSlot(0); - - endEffector.setControl(request.withPosition( - endEffector.getPosition().getValueAsDouble() + (RobotContainer.arm.deltaArmAngle() / 360))); - } - public boolean hasCoral() { return debouncer.calculate(endEffector.getStatorCurrent().getValueAsDouble() > 30); } From 5a8b4d6d4a5fd32c760b0d42c44cab6f4fa72e07 Mon Sep 17 00:00:00 2001 From: nh17000 <46301909+nh17000@users.noreply.github.com> Date: Fri, 9 May 2025 21:39:00 -0500 Subject: [PATCH 03/58] Simulate Drivetrain + EE, visualize CAD components this counts as studying for ap exams if i have heimler in the background --- simgui-ds.json | 10 +- simgui-window.json | 35 ++- simgui.json | 9 + src/main/java/frc/robot/Constants.java | 45 ++- src/main/java/frc/robot/Robot.java | 39 ++- src/main/java/frc/robot/RobotContainer.java | 70 ++++- src/main/java/frc/robot/Telemetry.java | 1 + .../java/frc/robot/subsystems/Arm/Arm.java | 9 + .../frc/robot/subsystems/Arm/ArmIOSim.java | 5 +- .../subsystems/CommandSwerveDrivetrain.java | 147 +++------ .../robot/subsystems/Elevator/Elevator.java | 9 +- .../subsystems/Elevator/ElevatorIOSim.java | 2 +- .../subsystems/Elevator/MechVisualizer.java | 67 ++++- .../frc/robot/subsystems/EndEffector.java | 235 --------------- .../subsystems/EndEffector/EndEffector.java | 160 ++++++++++ .../subsystems/EndEffector/EndEffectorIO.java | 20 ++ .../EndEffector/EndEffectorIOReal.java | 49 +++ .../EndEffector/EndEffectorIOSim.java | 281 ++++++++++++++++++ .../simulation/MapleSimSwerveDrivetrain.java | 269 +++++++++++++++++ 19 files changed, 1051 insertions(+), 411 deletions(-) delete mode 100644 src/main/java/frc/robot/subsystems/EndEffector.java create mode 100644 src/main/java/frc/robot/subsystems/EndEffector/EndEffector.java create mode 100644 src/main/java/frc/robot/subsystems/EndEffector/EndEffectorIO.java create mode 100644 src/main/java/frc/robot/subsystems/EndEffector/EndEffectorIOReal.java create mode 100644 src/main/java/frc/robot/subsystems/EndEffector/EndEffectorIOSim.java create mode 100644 src/main/java/frc/robot/util/simulation/MapleSimSwerveDrivetrain.java diff --git a/simgui-ds.json b/simgui-ds.json index a8c42be..a585da9 100644 --- a/simgui-ds.json +++ b/simgui-ds.json @@ -36,7 +36,7 @@ } ], "axisCount": 6, - "buttonCount": 8, + "buttonCount": 10, "buttonKeys": [ 90, 88, @@ -46,8 +46,8 @@ 69, -1, 266, - -1, - -1 + 53, + 54 ], "povConfig": [ { @@ -80,8 +80,8 @@ 44, 46, 47, - -1, - -1, + 45, + 61, 39, 267 ], diff --git a/simgui-window.json b/simgui-window.json index 05c68f4..5a7dbb2 100644 --- a/simgui-window.json +++ b/simgui-window.json @@ -6,16 +6,21 @@ "GLOBAL": { "font": "Proggy Dotted", "fps": "120", - "height": "1046", - "maximized": "1", + "height": "1033", + "maximized": "0", "style": "0", "userScale": "2", - "width": "1920", + "width": "956", "xpos": "0", "ypos": "34" } }, "Table": { + "0x965B9C9E,2": { + "Column 0 Width": "190", + "Column 1 Weight": "1.0000", + "RefScale": "19" + }, "0xE56EC1C2,4": { "Column 0 Weight": "1.0000", "Column 1 Weight": "1.0000", @@ -31,8 +36,8 @@ }, "###/SmartDashboard/Elevator Sim": { "Collapsed": "0", - "Pos": "532,30", - "Size": "357,694" + "Pos": "229,50", + "Size": "348,321" }, "###/SmartDashboard/Module 0": { "Collapsed": "0", @@ -46,32 +51,32 @@ }, "###FMS": { "Collapsed": "0", - "Pos": "8,699", + "Pos": "9,411", "Size": "235,244" }, "###Joysticks": { "Collapsed": "0", - "Pos": "292,408", - "Size": "1156,271" + "Pos": "324,436", + "Size": "950,287" }, "###Keyboard 0 Settings": { "Collapsed": "0", - "Pos": "985,23", + "Pos": "649,30", "Size": "300,560" }, "###Keyboard 1 Settings": { "Collapsed": "0", - "Pos": "1299,26", - "Size": "300,560" + "Pos": "937,31", + "Size": "300,552" }, "###NetworkTables": { "Collapsed": "0", - "Pos": "433,697", + "Pos": "446,644", "Size": "1125,349" }, "###NetworkTables Info": { "Collapsed": "0", - "Pos": "324,317", + "Pos": "557,706", "Size": "1125,217" }, "###Other Devices": { @@ -86,12 +91,12 @@ }, "###System Joysticks": { "Collapsed": "0", - "Pos": "0,399", + "Pos": "-1,597", "Size": "273,290" }, "###Timing": { "Collapsed": "0", - "Pos": "1,180", + "Pos": "1,179", "Size": "197,215" }, "Debug##Default": { diff --git a/simgui.json b/simgui.json index 399047e..1c87d43 100644 --- a/simgui.json +++ b/simgui.json @@ -60,8 +60,17 @@ } }, "NetworkTables Info": { + "Connections": { + "open": true + }, + "Server": { + "open": true + }, "visible": true }, + "NetworkTables View": { + "visible": false + }, "Plot": { "Plot <0>": { "plots": [ diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 9365ef2..34b16de 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -7,15 +7,32 @@ import edu.wpi.first.apriltag.AprilTagFields; import edu.wpi.first.math.VecBuilder; import edu.wpi.first.math.Vector; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Translation2d; import edu.wpi.first.math.numbers.N3; import edu.wpi.first.math.util.Units; import edu.wpi.first.units.measure.Dimensionless; import edu.wpi.first.units.measure.Frequency; import edu.wpi.first.units.measure.Time; +import edu.wpi.first.wpilibj.RobotBase; import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim; +import java.util.Arrays; +import java.util.List; public class Constants { + public static final Mode currentMode = RobotBase.isReal() ? Mode.REAL : Mode.SIM; + + public static enum Mode { + /** Running on a real robot. */ + REAL, + + /** Running a physics simulator. */ + SIM, + + /** Replaying from a log file. */ + REPLAY + } public static class VisionConstants { public static final String LL_NAME = "limelight-back"; @@ -56,6 +73,28 @@ public static final class FieldConstants { public static final Translation2d[] BLUE_CAGES = {BLUE_FAR_CAGE, BLUE_MID_CAGE, BLUE_CLOSE_CAGE}; public static final Translation2d[] RED_CAGES = {RED_FAR_CAGE, RED_MID_CAGE, RED_CLOSE_CAGE}; + + public static final Translation2d BLUE_REEF_CENTER = new Translation2d(4.5, 4); + + public static final Translation2d BLUE_NPS_CORAL_STATION = + new Translation2d(Units.inchesToMeters(33.526), Units.inchesToMeters(291.176)); + public static final Translation2d BLUE_PS_CORAL_STATION = + new Translation2d(Units.inchesToMeters(33.526), Units.inchesToMeters(25.824)); + + public static final Translation2d RED_NPS_CORAL_STATION = + new Translation2d(FIELD_LENGTH - Units.inchesToMeters(33.526), Units.inchesToMeters(291.176)); + public static final Translation2d RED_PS_CORAL_STATION = + new Translation2d(FIELD_LENGTH - Units.inchesToMeters(33.526), Units.inchesToMeters(25.824)); + + public static final List CORAL_STATIONS = Arrays.asList( + new Pose2d(BLUE_NPS_CORAL_STATION, new Rotation2d(125)), + new Pose2d(BLUE_PS_CORAL_STATION, new Rotation2d(-125)), + new Pose2d(RED_NPS_CORAL_STATION, new Rotation2d(-125)), + new Pose2d(RED_PS_CORAL_STATION, new Rotation2d(125))); + + // the top of the branch (L4) is ~2" behind the april tag + public static final double BRANCH_OFFSET_BEHIND_APRILTAG = Units.inchesToMeters(2.049849); + public static final double L4_HEIGHT = Units.inchesToMeters(72); } public static final class DriveConstants { @@ -269,6 +308,8 @@ public static final class EndEffectorConstants { public static final double PULL_SPEED = -0.3; public static final double PUSH_SPEED = 0.6; // 0.3 + public static final double L3_PUSH_SPEED = 0.3; // 0.3 + public static final double L2_PUSH_SPEED = 0.1; // 0.3 public static final double ALGAE_PULL_SPEED = 0.8; public static final double ALGAE_PUSH_SPEED = -1.0; @@ -314,8 +355,8 @@ public static class SimulationConstants { public static final double STARTING_HEIGHT = MIN_HEIGHT; // new EE viz - public static final double PIVOT_TO_MIDDLE_OF_CORAL_ANG_OFFSET = Units.degreesToRadians(-20.2531597269); + public static final double PIVOT_TO_MIDDLE_OF_CORAL_ANG_OFFSET = Units.degreesToRadians(20.2531597269); public static final double PIVOT_TO_MIDDLE_OF_CORAL_RADIUS = Units.inchesToMeters(23.249031544); - public static final double PIVOT_ANGLE_TO_CORAL_ANGLE = Units.degreesToRadians(243.986); + public static final double PIVOT_ANGLE_TO_CORAL_ANGLE = Units.degreesToRadians(-243.986); } } diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java index b9015e2..1225454 100644 --- a/src/main/java/frc/robot/Robot.java +++ b/src/main/java/frc/robot/Robot.java @@ -22,19 +22,26 @@ public class Robot extends LoggedRobot { public Robot() { Logger.recordMetadata("2025RobotCode", "Comp Bot Code"); // Set a metadata value - boolean isReplay = false; - if (isReal()) { // REAL - Logger.addDataReceiver(new WPILOGWriter("/media/sda1/")); // Log to a USB stick ("/U/logs") - Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables - } else if (!isReplay) { // SIM - Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables - } else { // REPLAY - setUseTiming(false); // Run as fast as possible - String logPath = // "/media/sda1/"; - LogFileUtil.findReplayLog(); // Pull the replay log from AdvantageScope (or prompt the user) - Logger.setReplaySource(new WPILOGReader(logPath)); // Read replay log - Logger.addDataReceiver( - new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"))); // Save outputs to a new log + // Set up data receivers & replay source + switch (Constants.currentMode) { + case REAL: + // Running on a real robot, log to a USB stick ("/U/logs") + Logger.addDataReceiver(new WPILOGWriter()); + Logger.addDataReceiver(new NT4Publisher()); + break; + + case SIM: + // Running a physics simulator, log to NT + Logger.addDataReceiver(new NT4Publisher()); + break; + + case REPLAY: + // Replaying a log, set up replay source + setUseTiming(false); // Run as fast as possible + String logPath = LogFileUtil.findReplayLog(); + Logger.setReplaySource(new WPILOGReader(logPath)); + Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"))); + break; } Logger.start(); @@ -49,7 +56,9 @@ public void robotPeriodic() { } @Override - public void disabledInit() {} + public void disabledInit() { + m_robotContainer.resetSimulation(); + } @Override public void disabledPeriodic() {} @@ -98,6 +107,8 @@ public void testExit() {} @Override public void simulationPeriodic() { + // ProjectileIntakeSim.getInstance().periodic(); MechVisualizer.getInstance().periodic(); + m_robotContainer.displaySimFieldToAdvantageScope(); } } diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 5446524..be061f1 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -8,6 +8,8 @@ import com.pathplanner.lib.auto.NamedCommands; import com.pathplanner.lib.commands.PathfindingCommand; import com.pathplanner.lib.events.EventTrigger; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.XboxController; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; @@ -29,15 +31,23 @@ import frc.robot.generated.TunerConstants; import frc.robot.subsystems.Arm.Arm; import frc.robot.subsystems.Arm.Arm.ArmMode; +import frc.robot.subsystems.Arm.ArmIO; import frc.robot.subsystems.Arm.ArmIOReal; import frc.robot.subsystems.Arm.ArmIOSim; import frc.robot.subsystems.Climber; import frc.robot.subsystems.CommandSwerveDrivetrain; import frc.robot.subsystems.Elevator.Elevator; +import frc.robot.subsystems.Elevator.ElevatorIO; import frc.robot.subsystems.Elevator.ElevatorIOReal; import frc.robot.subsystems.Elevator.ElevatorIOSim; -import frc.robot.subsystems.EndEffector; +import frc.robot.subsystems.EndEffector.EndEffector; +import frc.robot.subsystems.EndEffector.EndEffectorIO; +import frc.robot.subsystems.EndEffector.EndEffectorIOReal; +import frc.robot.subsystems.EndEffector.EndEffectorIOSim; +import frc.robot.util.simulation.MapleSimSwerveDrivetrain; import frc.robot.util.vision.PoseEstimation; +import org.ironmaple.simulation.SimulatedArena; +import org.littletonrobotics.junction.Logger; public class RobotContainer { private double MaxSpeed = TunerConstants.kSpeedAt12Volts.in(MetersPerSecond); @@ -45,7 +55,7 @@ public class RobotContainer { private Elevator elevator; private Arm arm; - public static final EndEffector endEffector = EndEffector.getInstance(); + private EndEffector endEffector; public static final Climber climber = Climber.getInstance(); public static final CommandSwerveDrivetrain drivetrain = TunerConstants.createDrivetrain(); public static final AutoAlign align = new AutoAlign(() -> drivetrain.getState().Pose); @@ -84,6 +94,11 @@ public class RobotContainer { private final Trigger strafe_Triggers = new Trigger( () -> Math.abs(driverController.getRightTriggerAxis() - driverController.getLeftTriggerAxis()) > 0.1); + private final JoystickButton csDropLB = + new JoystickButton(driverController, XboxController.Button.kLeftStick.value); + private final JoystickButton csDropRB = + new JoystickButton(driverController, XboxController.Button.kRightStick.value); + // Op Controller private final JoystickButton homeElevator_Start = new JoystickButton(opController, XboxController.Button.kStart.value); @@ -110,12 +125,28 @@ public class RobotContainer { public final SendableChooser autoChooser; public RobotContainer() { - if (Robot.isReal()) { - elevator = new Elevator(new ElevatorIOReal()); - arm = new Arm(new ArmIOReal()); - } else { - elevator = new Elevator(new ElevatorIOSim()); - arm = new Arm(new ArmIOSim()); + switch (Constants.currentMode) { + case REAL: // Real robot, instantiate hardware IO implementations + elevator = new Elevator(new ElevatorIOReal()); + arm = new Arm(new ArmIOReal()); + endEffector = new EndEffector(new EndEffectorIOReal()); + break; + + case SIM: // Sim robot, instantiate physics sim IO implementations + elevator = new Elevator(new ElevatorIOSim()); + arm = new Arm(new ArmIOSim()); + endEffector = new EndEffector(new EndEffectorIOSim( + () -> MapleSimSwerveDrivetrain.getSimulatedPose(), // drivetrain.getState().Pose, + () -> drivetrain.getState().Speeds, + () -> elevator.getElevatorPositionMeters(), + () -> arm.getArmAngleRadsToHorizontal())); + break; + + default: // Replayed robot, disable IO implementations + elevator = new Elevator(new ElevatorIO() {}); + arm = new Arm(new ArmIO() {}); + endEffector = new EndEffector(new EndEffectorIO() {}); + break; } setDefaultCommands(); @@ -133,6 +164,8 @@ public RobotContainer() { new EventTrigger("LevelFour") .onTrue(new InstantCommand(() -> elevator.setElevatorLevelFourMode()) .andThen(new InstantCommand(() -> arm.setArmL4()))); + + DriverStation.silenceJoystickConnectionWarning(Robot.isSimulation()); } private void configureBindings() { @@ -272,6 +305,11 @@ private void configureBindings() { .onFalse(new InstantCommand(() -> arm.setAligning(false)) .andThen(new InstantCommand(() -> elevator.setAligning(false)))); + // if (Constants.currentMode == Constants.Mode.SIM) { + // csDropLB.onTrue(new InstantCommand(() -> dropCoralFromStation(false)).ignoringDisable(true)); + // csDropRB.onTrue(new InstantCommand(() -> dropCoralFromStation(true)).ignoringDisable(true)); + // } + drivetrain.registerTelemetry(logger::telemeterize); } @@ -445,4 +483,20 @@ public void setDefaultCommands() { // climber.setDefaultCommand(new ClimbCommand()); // ledstrip.setDefaultCommand(ledstrip.defaultCommand(() -> endEffector.isCoral())); } + + public void resetSimulation() { + if (Constants.currentMode != Constants.Mode.SIM) return; + + drivetrain.resetPose(new Pose2d(10.118, 1.18, new Rotation2d())); + SimulatedArena.getInstance().resetFieldForAuto(); + } + + public void displaySimFieldToAdvantageScope() { + if (Constants.currentMode != Constants.Mode.SIM) return; + + Logger.recordOutput( + "FieldSimulation/Coral", SimulatedArena.getInstance().getGamePiecesArrayByType("Coral")); + Logger.recordOutput( + "FieldSimulation/Algae", SimulatedArena.getInstance().getGamePiecesArrayByType("Algae")); + } } diff --git a/src/main/java/frc/robot/Telemetry.java b/src/main/java/frc/robot/Telemetry.java index 0f19dfd..012c192 100644 --- a/src/main/java/frc/robot/Telemetry.java +++ b/src/main/java/frc/robot/Telemetry.java @@ -105,6 +105,7 @@ public void telemeterize(SwerveDriveState state) { driveTimestamp.set(state.Timestamp); driveOdometryFrequency.set(1.0 / state.OdometryPeriod); + // for some reason, if i try to log multiple Pose2d objects, advantagekit just explodes Logger.recordOutput("Telemetry/Pose", state.Pose); Logger.recordOutput("Telemetry/Speeds", state.Speeds); Logger.recordOutput("Telemetry/Module States", state.ModuleStates); diff --git a/src/main/java/frc/robot/subsystems/Arm/Arm.java b/src/main/java/frc/robot/subsystems/Arm/Arm.java index 6dad98a..d3892bf 100644 --- a/src/main/java/frc/robot/subsystems/Arm/Arm.java +++ b/src/main/java/frc/robot/subsystems/Arm/Arm.java @@ -7,6 +7,8 @@ import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants.ArmConstants; +import frc.robot.Constants.SimulationConstants; +import frc.robot.subsystems.Elevator.MechVisualizer; import frc.robot.util.SmarterDashboard; import org.littletonrobotics.junction.Logger; @@ -39,6 +41,8 @@ public void periodic() { io.updateInputs(inputs); Logger.processInputs("Arm", inputs); + MechVisualizer.getInstance().updateArmAngle(getArmAngleRadsToHorizontal()); + SmarterDashboard.putNumber("Arm/Angle degrees", getArmAngleDegrees()); SmarterDashboard.putNumber("Arm/Adjust", armAdjust); SmarterDashboard.putString("Arm/Mode", armMode.toString()); @@ -155,6 +159,11 @@ public double getArmAngleDegrees() { return Units.rotationsToDegrees(getPivotPosition()); } + public double getArmAngleRadsToHorizontal() { + return Units.rotationsToRadians(inputs.positionRots / ArmConstants.ARM_GEAR_RATIO) + + SimulationConstants.STARTING_ANGLE; + } + public double getFeedforwardVolts() { return 0.35 * Math.cos(-1 * Units.degreesToRadians(getArmAngleDegrees() - 96)); } diff --git a/src/main/java/frc/robot/subsystems/Arm/ArmIOSim.java b/src/main/java/frc/robot/subsystems/Arm/ArmIOSim.java index e051e64..84853c5 100644 --- a/src/main/java/frc/robot/subsystems/Arm/ArmIOSim.java +++ b/src/main/java/frc/robot/subsystems/Arm/ArmIOSim.java @@ -12,7 +12,6 @@ import frc.lib.drivers.PearadoxTalonFX; import frc.robot.Constants.ArmConstants; import frc.robot.Constants.SimulationConstants; -import frc.robot.subsystems.Elevator.MechVisualizer; public class ArmIOSim implements ArmIO { private SingleJointedArmSim armSim = new SingleJointedArmSim( @@ -84,7 +83,7 @@ public void updateInputs(ArmIOInputsAutoLogged inputs) { @Override public void runPosition(double setpoint, double feedforward) { - pivot.setControl(new PositionVoltage(-setpoint).withFeedForward(feedforward)); + pivot.setControl(new PositionVoltage(setpoint).withFeedForward(feedforward)); } private void updateSim() { @@ -100,6 +99,6 @@ private void updateSim() { pivotMotorSimState.setRotorVelocity( Units.radiansToRotations(armSim.getVelocityRadPerSec() * ArmConstants.ARM_GEAR_RATIO)); - MechVisualizer.getInstance().updateArmAngle(armSim.getAngleRads()); + // MechVisualizer.getInstance().updateArmAngle(armSim.getAngleRads()); } } diff --git a/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java b/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java index c0ec7c0..b5c4c34 100644 --- a/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java +++ b/src/main/java/frc/robot/subsystems/CommandSwerveDrivetrain.java @@ -14,28 +14,24 @@ import edu.wpi.first.math.Matrix; import edu.wpi.first.math.filter.SlewRateLimiter; 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.Transform2d; import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N3; -import edu.wpi.first.math.util.Units; +import edu.wpi.first.math.system.plant.DCMotor; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj.DriverStation.Alliance; import edu.wpi.first.wpilibj.Notifier; -import edu.wpi.first.wpilibj.RobotController; +import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Subsystem; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import frc.robot.Constants.DriveConstants; -import frc.robot.Constants.FieldConstants; -import frc.robot.Constants.VisionConstants; -import frc.robot.RobotContainer; +import frc.robot.generated.TunerConstants; import frc.robot.generated.TunerConstants.TunerSwerveDrivetrain; import frc.robot.util.SmarterDashboard; -import java.util.HashMap; -import java.util.Map; +import frc.robot.util.simulation.MapleSimSwerveDrivetrain; import java.util.function.Supplier; +import org.ironmaple.simulation.drivesims.COTS; /** * Class that extends the Phoenix 6 SwerveDrivetrain class and implements Subsystem so it can easily be used in @@ -130,7 +126,7 @@ public class CommandSwerveDrivetrain extends TunerSwerveDrivetrain implements Su */ public CommandSwerveDrivetrain( SwerveDrivetrainConstants drivetrainConstants, SwerveModuleConstants... modules) { - super(drivetrainConstants, modules); + super(drivetrainConstants, MapleSimSwerveDrivetrain.regulateModuleConstantsForSimulation(modules)); if (Utils.isSimulation()) { startSimThread(); } @@ -152,7 +148,10 @@ public CommandSwerveDrivetrain( SwerveDrivetrainConstants drivetrainConstants, double odometryUpdateFrequency, SwerveModuleConstants... modules) { - super(drivetrainConstants, odometryUpdateFrequency, modules); + super( + drivetrainConstants, + odometryUpdateFrequency, + MapleSimSwerveDrivetrain.regulateModuleConstantsForSimulation(modules)); if (Utils.isSimulation()) { startSimThread(); } @@ -185,7 +184,7 @@ public CommandSwerveDrivetrain( odometryUpdateFrequency, odometryStandardDeviation, visionStandardDeviation, - modules); + MapleSimSwerveDrivetrain.regulateModuleConstantsForSimulation(modules)); if (Utils.isSimulation()) { startSimThread(); } @@ -269,26 +268,29 @@ public void periodic() { m_hasAppliedOperatorPerspective = true; }); } - - Transform2d offset = getState().Pose.minus(getTagPose(currentCSAlignTagID)); - - SmarterDashboard.putNumber("Drive/X", offset.getX()); - SmarterDashboard.putNumber("Drive/Y", offset.getY()); SmarterDashboard.putBoolean("Drive/Slow Mode", isSlowMode); } - private void startSimThread() { - m_lastSimTime = Utils.getCurrentTimeSeconds(); + private MapleSimSwerveDrivetrain mapleSimSwerveDrivetrain = null; + private void startSimThread() { + mapleSimSwerveDrivetrain = new MapleSimSwerveDrivetrain( + Seconds.of(kSimLoopPeriod), + Pounds.of(115), // robot weight + Inches.of(30), // bumper length + Inches.of(30), // bumper width + DCMotor.getKrakenX60(1), // drive motor type + DCMotor.getKrakenX60(1), // steer motor type + COTS.WHEELS.VEX_GRIP_V2.cof, // wheel COF + getModuleLocations(), + getPigeon2(), + getModules(), + TunerConstants.FrontLeft, + TunerConstants.FrontRight, + TunerConstants.BackLeft, + TunerConstants.BackRight); /* Run simulation at a faster rate so PID gains behave more reasonably */ - m_simNotifier = new Notifier(() -> { - final double currentTime = Utils.getCurrentTimeSeconds(); - double deltaTime = currentTime - m_lastSimTime; - m_lastSimTime = currentTime; - - /* use the measured time delta, get battery voltage from WPILib */ - updateSimState(deltaTime, RobotController.getBatteryVoltage()); - }); + m_simNotifier = new Notifier(mapleSimSwerveDrivetrain::update); m_simNotifier.startPeriodic(kSimLoopPeriod); } @@ -341,91 +343,10 @@ public double getSpeedMultipler() { return speedMultiplier; } - private int currentReefAlignTagID = 18; // -1 - private int currentCSAlignTagID = 12; // -1 - private Map tagPoses3d = getTagPoses(); - - public Map getTagPoses() { - Map tagPoses = new HashMap(); - for (int tag : FieldConstants.RED_REEF_TAG_IDS) { - tagPoses.put(tag, VisionConstants.aprilTagLayout.getTagPose(tag).get()); - } - for (int tag : FieldConstants.BLUE_REEF_TAG_IDS) { - tagPoses.put(tag, VisionConstants.aprilTagLayout.getTagPose(tag).get()); - } - for (int tag : FieldConstants.RED_CORAL_STATION_TAG_IDS) { - tagPoses.put(tag, VisionConstants.aprilTagLayout.getTagPose(tag).get()); - } - for (int tag : FieldConstants.BLUE_CORAL_STATION_TAG_IDS) { - tagPoses.put(tag, VisionConstants.aprilTagLayout.getTagPose(tag).get()); - } - return tagPoses; - } - - private Rotation2d getTagAngle(int tagID) { - - if (tagPoses3d.containsKey(tagID)) { - Pose3d tagPose = tagPoses3d.get(tagID); - return new Rotation2d(tagPose.getRotation().getZ()); - } else return new Rotation2d(0); - } - - private Pose2d getTagPose(int tagID) { - - if (tagPoses3d.containsKey(tagID)) { - Pose3d tagPose = tagPoses3d.get(tagID); - return tagPose.toPose2d(); - } else return new Pose2d(); - } - - public Rotation2d getAlignAngleReef() { - currentReefAlignTagID = getClosestAprilTag( - RobotContainer.isRedAlliance() ? FieldConstants.RED_REEF_TAG_IDS : FieldConstants.BLUE_REEF_TAG_IDS, - getState().Pose); - - return getTagAngle(currentReefAlignTagID); - } - - public Rotation2d getAlignAngleAlgaeReef() { - currentReefAlignTagID = getClosestAprilTag( - RobotContainer.isRedAlliance() ? FieldConstants.RED_REEF_TAG_IDS : FieldConstants.BLUE_REEF_TAG_IDS, - getState().Pose); - - return new Rotation2d(getTagAngle(currentReefAlignTagID).getRadians() + Units.degreesToRadians(180)); - } - - public Rotation2d getAlignAngleStation() { - currentCSAlignTagID = getClosestAprilTag( - RobotContainer.isRedAlliance() - ? FieldConstants.RED_CORAL_STATION_TAG_IDS - : FieldConstants.BLUE_CORAL_STATION_TAG_IDS, - getState().Pose); - - return new Rotation2d(getTagAngle(currentCSAlignTagID).getRadians() + +Units.degreesToRadians(180)); - } - - private int getClosestAprilTag(int[] tagIDs, Pose2d robotPose) { - double minDistance = Double.POSITIVE_INFINITY; - int closestTagID = -1; - - // iterates through all tag IDs - for (int i : tagIDs) { - if (tagPoses3d.containsKey(i)) { - Pose3d tagPose = tagPoses3d.get(i); - - // distance between robot pose and april tag - double distance = tagPose.getTranslation() - .toTranslation2d() - .minus(robotPose.getTranslation()) - .getNorm(); - - if (distance < minDistance) { - closestTagID = i; - minDistance = distance; - } - } - } - - return closestTagID; + @Override + public void resetPose(Pose2d pose) { + if (this.mapleSimSwerveDrivetrain != null) mapleSimSwerveDrivetrain.mapleSimDrive.setSimulationWorldPose(pose); + Timer.delay(0.1); // Wait for simulation to update + super.resetPose(pose); } } diff --git a/src/main/java/frc/robot/subsystems/Elevator/Elevator.java b/src/main/java/frc/robot/subsystems/Elevator/Elevator.java index 2fde0f6..41a6bda 100644 --- a/src/main/java/frc/robot/subsystems/Elevator/Elevator.java +++ b/src/main/java/frc/robot/subsystems/Elevator/Elevator.java @@ -4,6 +4,7 @@ package frc.robot.subsystems.Elevator; +import edu.wpi.first.math.util.Units; import edu.wpi.first.wpilibj.DriverStation; import edu.wpi.first.wpilibj2.command.SubsystemBase; import frc.robot.Constants.ElevatorConstants; @@ -13,7 +14,7 @@ public class Elevator extends SubsystemBase { private double elevatorOffset = 0.0; - private boolean isCoral = false; + private boolean isCoral = true; private boolean isAligning = false; private boolean isZeroing = false; @@ -43,6 +44,8 @@ public void periodic() { io.updateInputs(inputs); Logger.processInputs("Elevator", inputs); + MechVisualizer.getInstance().updateElevatorHeight(getElevatorPositionMeters()); + SmarterDashboard.putNumber("Elevator/Offset", elevatorOffset); SmarterDashboard.putString("Elevator Mode", elevatorMode.toString()); SmarterDashboard.putBoolean("Elevator/IsCoral", isCoral); @@ -133,6 +136,10 @@ public double getElevatorPositionInches() { return getElevatorPositionRots() * ElevatorConstants.kRotationToInches; } + public double getElevatorPositionMeters() { + return Units.inchesToMeters(getElevatorPositionInches()); + } + public double getElevatorVelocityInchesPerSecond() { return getElevatorVelocity_RotsPerSecond() * ElevatorConstants.kRotationToInches; } diff --git a/src/main/java/frc/robot/subsystems/Elevator/ElevatorIOSim.java b/src/main/java/frc/robot/subsystems/Elevator/ElevatorIOSim.java index 322d269..b79c0d0 100644 --- a/src/main/java/frc/robot/subsystems/Elevator/ElevatorIOSim.java +++ b/src/main/java/frc/robot/subsystems/Elevator/ElevatorIOSim.java @@ -106,7 +106,7 @@ private void updateSim() { / (2.0 * Math.PI)) * ElevatorConstants.GEAR_RATIO); - MechVisualizer.getInstance().updateElevatorHeight(elevatorSim.getPositionMeters()); + // MechVisualizer.getInstance().updateElevatorHeight(elevatorSim.getPositionMeters()); } private static double getMotorRotations(double linearDisplacement) { diff --git a/src/main/java/frc/robot/subsystems/Elevator/MechVisualizer.java b/src/main/java/frc/robot/subsystems/Elevator/MechVisualizer.java index a772578..915cce2 100644 --- a/src/main/java/frc/robot/subsystems/Elevator/MechVisualizer.java +++ b/src/main/java/frc/robot/subsystems/Elevator/MechVisualizer.java @@ -1,5 +1,8 @@ package frc.robot.subsystems.Elevator; +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.util.Units; import edu.wpi.first.wpilibj.smartdashboard.Mechanism2d; import edu.wpi.first.wpilibj.smartdashboard.MechanismLigament2d; @@ -7,7 +10,10 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj.util.Color; import edu.wpi.first.wpilibj.util.Color8Bit; +import frc.robot.Constants.AlignConstants; import frc.robot.Constants.SimulationConstants; +import frc.robot.RobotContainer; +import org.littletonrobotics.junction.Logger; public class MechVisualizer { private final double elevatorAngle = 90; // straight up @@ -32,8 +38,10 @@ public class MechVisualizer { "EE23a", Units.inchesToMeters(5.6102), 180 - 109.295, 7, new Color8Bit(Color.kDarkSeaGreen))); private MechanismLigament2d ee34a = ee23a.append(new MechanismLigament2d( "EE34a", Units.inchesToMeters(2), -(180 - 163.914), 7, new Color8Bit(Color.kMediumSeaGreen))); - private MechanismLigament2d ee45a = ee34a.append(new MechanismLigament2d( - "EE45a", Units.inchesToMeters(5.1181), -(180 - 151.395), 7, new Color8Bit(Color.kLightSeaGreen))); + private MechanismLigament2d ee45a1 = ee34a.append(new MechanismLigament2d( + "EE45a1", Units.inchesToMeters(5.1181 / 2), -(180 - 151.395), 7, new Color8Bit(Color.kLightSeaGreen))); + private MechanismLigament2d ee45a2 = ee45a1.append( + new MechanismLigament2d("EE45a2", Units.inchesToMeters(5.1181 / 2), 0, 7, new Color8Bit(Color.kPaleGreen))); private MechanismLigament2d ee23b = arm.append(new MechanismLigament2d( "EE23b", Units.inchesToMeters(5.6102), 180 + 109.295, 7, new Color8Bit(Color.kDarkBlue))); @@ -44,19 +52,31 @@ public class MechVisualizer { private MechanismLigament2d ee45b2 = ee45b1.append( new MechanismLigament2d("EE45b2", Units.inchesToMeters(5.1181 / 2), 0, 7, new Color8Bit(Color.kSkyBlue))); - private MechanismLigament2d coral1 = ee45b1.append(new MechanismLigament2d( - "CORAL1", SimulationConstants.CORAL_LENGTH / 2, 90, 10, new Color8Bit(Color.kPapayaWhip))); - private MechanismLigament2d coral2 = ee45b1.append(new MechanismLigament2d( - "CORAL2", SimulationConstants.CORAL_LENGTH / 2, -90, 10, new Color8Bit(Color.kAntiqueWhite))); + // private MechanismLigament2d coral1 = ee45b1.append(new MechanismLigament2d( + // "CORAL1", SimulationConstants.CORAL_LENGTH / 2, 90, 10, new Color8Bit(Color.kPapayaWhip))); + // private MechanismLigament2d coral2 = ee45b1.append(new MechanismLigament2d( + // "CORAL2", SimulationConstants.CORAL_LENGTH / 2, -90, 10, new Color8Bit(Color.kAntiqueWhite))); - private MechanismLigament2d coral3 = coral2.append(new MechanismLigament2d( - "CORAL3", Units.inchesToMeters(23.4106654653), 180 - 278.855350292, 1, new Color8Bit(Color.kCyan))); + private MechanismLigament2d coral1a = ee45a1.append(new MechanismLigament2d( + "CORAL1a", SimulationConstants.CORAL_LENGTH / 2.0, 90, 8, new Color8Bit(Color.kPapayaWhip))); + private MechanismLigament2d coral2a = ee45a1.append(new MechanismLigament2d( + "CORAL2a", SimulationConstants.CORAL_LENGTH / 2.0, -90, 8, new Color8Bit(Color.kAntiqueWhite))); - private MechanismLigament2d coral4 = ee45b1.append(new MechanismLigament2d( - "CORAL4", Units.inchesToMeters(23.249031544), 180 - 354.239159727, 1, new Color8Bit(Color.kRed))); + // private MechanismLigament2d coral3 = coral2.append(new MechanismLigament2d( + // "CORAL3", Units.inchesToMeters(23.4106654653), 180 - 278.855350292, 1, new Color8Bit(Color.kCyan))); + // private MechanismLigament2d coral4 = ee45b1.append(new MechanismLigament2d( + // "CORAL4", Units.inchesToMeters(23.249031544), 180 - 354.239159727, 1, new Color8Bit(Color.kRed))); + + // private MechanismLigament2d coral3a = coral1a.append(new MechanismLigament2d( + // "CORAL3a", Units.inchesToMeters(23.4106654653), 180 + 278.855350292, 1, new Color8Bit(Color.kCyan))); + // private MechanismLigament2d coral4a = ee45a1.append(new MechanismLigament2d( + // "CORAL4a", Units.inchesToMeters(23.249031544), 180 + 354.239159727, 1, new Color8Bit(Color.kRed))); // private InterpolatingDoubleTreeMap camLerp = new InterpolatingDoubleTreeMap(); + private double heightMeters = 0.0; + private double armAngleRads = 0.0; + private static final MechVisualizer instance = new MechVisualizer(); public static MechVisualizer getInstance() { @@ -73,17 +93,36 @@ private MechVisualizer() { public void periodic() { SmartDashboard.putData("Elevator Sim", mech2d); + + Logger.recordOutput("Sim/Origin", new Pose3d()); + + double armX = RobotContainer.driverController.getRightTriggerAxis(); + double armY = 0.342 + RobotContainer.driverController.getRightY(); + double armZ = 0.229 + RobotContainer.driverController.getLeftTriggerAxis(); // TODO: lower + double armP = RobotContainer.driverController.getRightX() * 2 * Math.PI; + + Logger.recordOutput("Sim/Arm", new double[] {armX, armY, armZ, 0, armP, 0}); + + Logger.recordOutput("Sim/Transforms", new Transform3d[] { + new Transform3d(0, 0, heightMeters, new Rotation3d()), + new Transform3d( + 0, + 0, + 1.003 + heightMeters, + new Rotation3d(0, -armAngleRads + SimulationConstants.STARTING_ANGLE, 0)), + new Transform3d(armX, armY, armZ, new Rotation3d(armP, 0, 0)) + }); } public void updateElevatorHeight(double heightMeters) { - heightMeters += Units.inchesToMeters(39); - elevator2d.setLength(heightMeters); + this.heightMeters = heightMeters; + elevator2d.setLength(heightMeters + AlignConstants.ELEVATOR_STARTING_HEIGHT); // ProjectileIntakeSim.getInstance().updateElevatorHeight(heightMeters); } public void updateArmAngle(double angleRads) { - double angleDegs = Units.radiansToDegrees(angleRads); - arm.setAngle(angleDegs - elevatorAngle); + this.armAngleRads = angleRads; + arm.setAngle(Units.radiansToDegrees(angleRads) - elevatorAngle); // double camAngle = camLerp.get(angleDegs); // ee_A.setAngle(camAngle - angleDegs); // parallel with coral diff --git a/src/main/java/frc/robot/subsystems/EndEffector.java b/src/main/java/frc/robot/subsystems/EndEffector.java deleted file mode 100644 index de8ed04..0000000 --- a/src/main/java/frc/robot/subsystems/EndEffector.java +++ /dev/null @@ -1,235 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package frc.robot.subsystems; - -import com.ctre.phoenix6.BaseStatusSignal; -import com.ctre.phoenix6.configs.Slot0Configs; -import com.ctre.phoenix6.signals.NeutralModeValue; -import edu.wpi.first.math.filter.Debouncer; -import edu.wpi.first.math.filter.Debouncer.DebounceType; -import edu.wpi.first.wpilibj.DigitalInput; -import edu.wpi.first.wpilibj.DriverStation; -import edu.wpi.first.wpilibj2.command.SubsystemBase; -import frc.lib.drivers.PearadoxTalonFX; -import frc.robot.Constants.ArmConstants; -import frc.robot.Constants.EndEffectorConstants; -import frc.robot.RobotContainer; -import frc.robot.subsystems.Arm.Arm; -import frc.robot.subsystems.Arm.Arm.ArmMode; -import frc.robot.util.SmarterDashboard; - -public class EndEffector extends SubsystemBase { - - private static final EndEffector END_EFFECTOR = new EndEffector(); - - private static final LEDStrip leds = LEDStrip.getInstance(); - - public static EndEffector getInstance() { - return END_EFFECTOR; - } - - private PearadoxTalonFX endEffector; - private DigitalInput endSensor; - private Debouncer debouncer; - - private boolean rumbled = false; - private boolean isIntaking = false; - private boolean isCoral = true; // TODO: integrate with arm - private boolean isHoldingCoral = true; - private boolean isHoldingAlgae = false; - private boolean holdSpeed = false; - - private double lastRot = 0; - - private static enum EEMode { - INTAKEMODE, - OUTTAKEMODE - } - - public EndEffector() { - endEffector = new PearadoxTalonFX(EndEffectorConstants.END_EFFECTOR_ID, NeutralModeValue.Brake, 60, false); - endSensor = new DigitalInput(EndEffectorConstants.END_SENSOR_CHANNEL); - debouncer = new Debouncer(0.125, DebounceType.kRising); - - BaseStatusSignal.setUpdateFrequencyForAll( - ArmConstants.UPDATE_FREQ, - endEffector.getPosition(), - endEffector.getVelocity(), - endEffector.getDutyCycle(), - endEffector.getMotorVoltage(), - endEffector.getTorqueCurrent(), - endEffector.getSupplyCurrent(), - endEffector.getStatorCurrent()); - SmarterDashboard.putNumber("EE/EE Speed", isCoral ? -0.15 : 0.1); - - var slot0Configs = new Slot0Configs(); - slot0Configs.kP = 0.2; - slot0Configs.kI = 0; - slot0Configs.kD = 0; - - endEffector.getConfigurator().apply(slot0Configs); - } - - @Override - public void periodic() { - collectGamePiece(); - - SmarterDashboard.putBoolean("EE/Holding Coral", isHoldingCoral); - SmarterDashboard.putBoolean("EE/Holding Algae", isHoldingAlgae); - SmarterDashboard.putBoolean("EE/Has Coral", hasCoral()); - SmarterDashboard.putBoolean("EE/Holding Speed", holdSpeed); - - SmarterDashboard.putNumber( - "EE/Stator Current", endEffector.getStatorCurrent().getValueAsDouble()); - SmarterDashboard.putNumber( - "EE/Supply Current", endEffector.getSupplyCurrent().getValueAsDouble()); - SmarterDashboard.putNumber("EE/Volts", endEffector.getMotorVoltage().getValueAsDouble()); - SmarterDashboard.putNumber( - "EE/Angular Velocity", endEffector.getVelocity().getValueAsDouble()); - } - - // public void collectCoral() { - // if (DriverStation.isTeleop()) { - // if (RobotContainer.opController.getRightTriggerAxis() >= 0.25) { - // coralIn(); - // isHolding = false; - // } else if (RobotContainer.opController.getLeftTriggerAxis() >= 0.25) { - // coralOut(); - // isHolding = false; - // } else if (hasCoral() && isCoral) { - // stop(); - // } else if (!isHolding) { - // holdCoral(); - // } - // } - // } - public void collectGamePiece() { - if (DriverStation.isTeleop()) { - // if(isCoral) { - if (RobotContainer.driverController.getLeftBumperButton()) { - if (isCoral) { - coralIn(); - holdSpeed = false; - } else if (!isCoral) { - algaeIn(); - holdSpeed = true; - } - isHoldingCoral = false; - } else if (RobotContainer.driverController.getRightBumperButton()) { - if (isCoral) { - coralOut(); - } else if (!isCoral) { - algaeOut(); - } - - holdSpeed = false; - isHoldingCoral = false; - } else { - if (!holdSpeed) { - stop(); - } - if (isCoral) { - holdCoral(); - } - } - - // if (endEffector.getStatorCurrent().getValueAsDouble() > 35.0) { - // leds.setLEDsFlash(); - // leds.handleFlashing(); - // } else leds.stopFlashing(); - } - } - - // else if(!isCoral) { - // if(RobotContainer.opController.getRightTriggerAxis() >= 0.25) { - // algaeIn(); - // isHoldingAlgae = true; - // } - // else if(RobotContainer.opController.getLeftTriggerAxis() >= 0.25) { - // algaeOut(); - // isHoldingAlgae = false; - // } - // else if(isHoldingAlgae) { - // stopAlgae(); - // } - // } - // } - - // scores - public void coralIn() { - endEffector.set(EndEffectorConstants.PULL_SPEED); - setLastRot(); - } - - public void algaeIn() { - endEffector.set(EndEffectorConstants.ALGAE_PULL_SPEED); - } - - public void algaeOut() { - endEffector.set(EndEffectorConstants.ALGAE_PUSH_SPEED); - } - - // intakes - public void coralOut() { - if (Arm.getArmMode() == ArmMode.L2 || Arm.getArmMode() == ArmMode.Stowed) { - endEffector.set(0.1); - } else if (Arm.getArmMode() == ArmMode.L3) { - endEffector.set(0.3); - } else endEffector.set(EndEffectorConstants.PUSH_SPEED); - setLastRot(); - } - - public void holdCoral() { - // endEffector.set(SmartDashboard.getNumber("EE/EE Speed", isCoral ? -0.15 : 0.1)); - endEffector.set(EndEffectorConstants.HOLD_SPEED); - setLastRot(); - } - - public void holdAlgae() { - endEffector.set(EndEffectorConstants.ALGAE_PULL_SPEED); - } - - public void stopCoral() { - stop(); - isHoldingCoral = true; - } - - public void stopAlgae() { - stop(); - isHoldingAlgae = true; - } - - public void stop() { - endEffector.set(0); - } - - public boolean hasCoral() { - return debouncer.calculate(endEffector.getStatorCurrent().getValueAsDouble() > 30); - } - - public boolean getHolding() { - return isHoldingCoral; - } - - public void setHolding(boolean hold) { - isHoldingCoral = hold; - } - - public void setLastRot() { - lastRot = endEffector.getPosition().getValueAsDouble(); - } - - public void setCoral() { - isCoral = true; - } - - public void setAlgae() { - isCoral = false; - } - - public boolean isCoral() { - return isCoral; - } -} diff --git a/src/main/java/frc/robot/subsystems/EndEffector/EndEffector.java b/src/main/java/frc/robot/subsystems/EndEffector/EndEffector.java new file mode 100644 index 0000000..8f7c57f --- /dev/null +++ b/src/main/java/frc/robot/subsystems/EndEffector/EndEffector.java @@ -0,0 +1,160 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package frc.robot.subsystems.EndEffector; + +import edu.wpi.first.math.filter.Debouncer; +import edu.wpi.first.math.filter.Debouncer.DebounceType; +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants.EndEffectorConstants; +import frc.robot.RobotContainer; +import frc.robot.subsystems.Arm.Arm; +import frc.robot.subsystems.Arm.Arm.ArmMode; +import frc.robot.util.SmarterDashboard; +import org.littletonrobotics.junction.Logger; + +public class EndEffector extends SubsystemBase { + private Debouncer debouncer; + + private boolean isCoral = true; + private boolean isHoldingCoral = true; + private boolean isHoldingAlgae = false; + private boolean holdSpeed = false; + + private double lastRot = 0; + + private EndEffectorIO io; + private final EndEffectorIOInputsAutoLogged inputs = new EndEffectorIOInputsAutoLogged(); + + public EndEffector(EndEffectorIO io) { + this.io = io; + + debouncer = new Debouncer(0.125, DebounceType.kRising); + + SmarterDashboard.putNumber("EE/EE Speed", isCoral ? -0.15 : 0.1); + } + + @Override + public void periodic() { + io.updateInputs(inputs); + Logger.processInputs("EE", inputs); + + collectGamePiece(); + + SmarterDashboard.putBoolean("EE/Holding Coral", isHoldingCoral); + SmarterDashboard.putBoolean("EE/Holding Algae", isHoldingAlgae); + SmarterDashboard.putBoolean("EE/Has Coral", hasCoral()); + SmarterDashboard.putBoolean("EE/Holding Speed", holdSpeed); + } + + public void collectGamePiece() { + if (DriverStation.isTeleop()) { + if (RobotContainer.driverController.getLeftBumperButton()) { + if (isCoral) { + coralIn(); + holdSpeed = false; + } else if (!isCoral) { + algaeIn(); + holdSpeed = true; + } + isHoldingCoral = false; + } else if (RobotContainer.driverController.getRightBumperButton()) { + if (isCoral) { + coralOut(); + } else if (!isCoral) { + algaeOut(); + } + + holdSpeed = false; + isHoldingCoral = false; + } else { + if (!holdSpeed) { + stop(); + } + if (isCoral) { + holdCoral(); + } + } + } + } + + // scores + public void coralIn() { + io.setSpeed(EndEffectorConstants.PULL_SPEED); + setLastRot(); + } + + public void algaeIn() { + io.setSpeed(EndEffectorConstants.ALGAE_PULL_SPEED); + } + + public void algaeOut() { + io.setSpeed(EndEffectorConstants.ALGAE_PUSH_SPEED); + } + + // intakes + public void coralOut() { + if (Arm.getArmMode() == ArmMode.L2 || Arm.getArmMode() == ArmMode.Stowed) { + io.setSpeed(EndEffectorConstants.L2_PUSH_SPEED); + } else if (Arm.getArmMode() == ArmMode.L3) { + io.setSpeed(EndEffectorConstants.L3_PUSH_SPEED); + } else { + io.setSpeed(EndEffectorConstants.PUSH_SPEED); + } + setLastRot(); + } + + public void holdCoral() { + // endEffector.set(SmartDashboard.getNumber("EE/EE Speed", isCoral ? -0.15 : 0.1)); + io.setSpeed(EndEffectorConstants.HOLD_SPEED); + setLastRot(); + } + + public void holdAlgae() { + io.setSpeed(EndEffectorConstants.ALGAE_PULL_SPEED); + } + + public void stopCoral() { + stop(); + isHoldingCoral = true; + } + + public void stopAlgae() { + stop(); + isHoldingAlgae = true; + } + + public void stop() { + io.setSpeed(0); + } + + public boolean hasCoral() { + return debouncer.calculate(inputs.statorCurrent > 30); + } + + public boolean getHolding() { + return isHoldingCoral; + } + + public void setHolding(boolean hold) { + isHoldingCoral = hold; + } + + public void setLastRot() { + lastRot = inputs.positionRots; + } + + public void setCoral() { + isCoral = true; + } + + public void setAlgae() { + isCoral = false; + } + + public boolean isCoral() { + return isCoral; + } +} diff --git a/src/main/java/frc/robot/subsystems/EndEffector/EndEffectorIO.java b/src/main/java/frc/robot/subsystems/EndEffector/EndEffectorIO.java new file mode 100644 index 0000000..6a81091 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/EndEffector/EndEffectorIO.java @@ -0,0 +1,20 @@ +package frc.robot.subsystems.EndEffector; + +import org.littletonrobotics.junction.AutoLog; + +public interface EndEffectorIO { + @AutoLog + public static class EndEffectorIOInputs { + public double positionRots = 0.0; + public double velocityRps = 0.0; + + public double appliedVolts = 0.0; + + public double statorCurrent = 0.0; + public double supplyCurrent = 0.0; + } + + public default void updateInputs(EndEffectorIOInputs inputs) {} + + public default void setSpeed(double speed) {} +} diff --git a/src/main/java/frc/robot/subsystems/EndEffector/EndEffectorIOReal.java b/src/main/java/frc/robot/subsystems/EndEffector/EndEffectorIOReal.java new file mode 100644 index 0000000..b166bf3 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/EndEffector/EndEffectorIOReal.java @@ -0,0 +1,49 @@ +package frc.robot.subsystems.EndEffector; + +import com.ctre.phoenix6.BaseStatusSignal; +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.signals.NeutralModeValue; +import frc.lib.drivers.PearadoxTalonFX; +import frc.robot.Constants.ArmConstants; +import frc.robot.Constants.EndEffectorConstants; + +public class EndEffectorIOReal implements EndEffectorIO { + private PearadoxTalonFX endEffector; + + public EndEffectorIOReal() { + endEffector = new PearadoxTalonFX(EndEffectorConstants.END_EFFECTOR_ID, NeutralModeValue.Brake, 60, false); + + BaseStatusSignal.setUpdateFrequencyForAll( + ArmConstants.UPDATE_FREQ, + endEffector.getPosition(), + endEffector.getVelocity(), + endEffector.getDutyCycle(), + endEffector.getMotorVoltage(), + endEffector.getTorqueCurrent(), + endEffector.getSupplyCurrent(), + endEffector.getStatorCurrent()); + + var slot0Configs = new Slot0Configs(); + slot0Configs.kP = 0.2; + slot0Configs.kI = 0; + slot0Configs.kD = 0; + + endEffector.getConfigurator().apply(slot0Configs); + } + + @Override + public void updateInputs(EndEffectorIOInputs inputs) { + inputs.positionRots = endEffector.getPosition().getValueAsDouble(); + inputs.velocityRps = endEffector.getVelocity().getValueAsDouble(); + + inputs.appliedVolts = endEffector.getMotorVoltage().getValueAsDouble(); + + inputs.statorCurrent = endEffector.getStatorCurrent().getValueAsDouble(); + inputs.supplyCurrent = endEffector.getSupplyCurrent().getValueAsDouble(); + } + + @Override + public void setSpeed(double speed) { + endEffector.set(speed); + } +} diff --git a/src/main/java/frc/robot/subsystems/EndEffector/EndEffectorIOSim.java b/src/main/java/frc/robot/subsystems/EndEffector/EndEffectorIOSim.java new file mode 100644 index 0000000..dfc1b09 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/EndEffector/EndEffectorIOSim.java @@ -0,0 +1,281 @@ +package frc.robot.subsystems.EndEffector; + +import static edu.wpi.first.units.Units.*; + +import com.ctre.phoenix6.BaseStatusSignal; +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.signals.NeutralModeValue; +import com.ctre.phoenix6.sim.TalonFXSimState; +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 edu.wpi.first.math.kinematics.ChassisSpeeds; +import edu.wpi.first.math.util.Units; +import edu.wpi.first.wpilibj.Timer; +import frc.lib.drivers.PearadoxTalonFX; +import frc.robot.Constants.AlignConstants; +import frc.robot.Constants.ArmConstants; +import frc.robot.Constants.EndEffectorConstants; +import frc.robot.Constants.FieldConstants; +import frc.robot.Constants.SimulationConstants; +import java.util.HashSet; +import java.util.Set; +import java.util.function.DoubleSupplier; +import java.util.function.Supplier; +import org.ironmaple.simulation.SimulatedArena; +import org.ironmaple.simulation.gamepieces.GamePieceProjectile; +import org.ironmaple.simulation.seasonspecific.reefscape2025.ReefscapeCoralOnFly; +import org.littletonrobotics.junction.Logger; + +public class EndEffectorIOSim implements EndEffectorIO { + private PearadoxTalonFX endEffector; + private TalonFXSimState endEffectorSimState; + + // must be within 6 inches of the intake + private static final double TRANSLATIONAL_TOLERANCE_METERS = Units.inchesToMeters(12); + // any rotation is fine + private static final double ROTATIONAL_TOLERANCE_RADIANS = Double.POSITIVE_INFINITY; + + private boolean hasCoral = true; + + private Timer intakingTimer = new Timer(); + private static final double INTAKING_TIME = 0.75; + + // cooldown between shooting and rerunning the intake + private Timer shootingTimer = new Timer(); + private static final double SHOOTING_TIME = 0.75; + private boolean disableIntake = false; + + private Timer droppingTimer = new Timer(); + private static final double DROP_COOLDOWN = 1.5; + + private Pose3d intookGamePiecePrevPose = Pose3d.kZero; + + private Supplier poseSupplier; + private Supplier chassisSpeedsSupplier; + private DoubleSupplier elevatorHeightSupplier; + private DoubleSupplier armAngleSupplier; + + public EndEffectorIOSim( + Supplier poseSupplier, + Supplier chassisSpeedsSupplier, + DoubleSupplier elevatorHeightSupplier, + DoubleSupplier armAngleSupplier) { + + this.poseSupplier = poseSupplier; + this.chassisSpeedsSupplier = chassisSpeedsSupplier; + this.elevatorHeightSupplier = elevatorHeightSupplier; + this.armAngleSupplier = armAngleSupplier; + + endEffector = new PearadoxTalonFX(EndEffectorConstants.END_EFFECTOR_ID, NeutralModeValue.Brake, 60, false); + + BaseStatusSignal.setUpdateFrequencyForAll( + ArmConstants.UPDATE_FREQ, + endEffector.getPosition(), + endEffector.getVelocity(), + endEffector.getDutyCycle(), + endEffector.getMotorVoltage(), + endEffector.getTorqueCurrent(), + endEffector.getSupplyCurrent(), + endEffector.getStatorCurrent()); + + var slot0Configs = new Slot0Configs(); + slot0Configs.kP = 0.2; + slot0Configs.kI = 0; + slot0Configs.kD = 0; + + endEffector.getConfigurator().apply(slot0Configs); + + endEffectorSimState = endEffector.getSimState(); + } + + @Override + public void updateInputs(EndEffectorIOInputs inputs) { + intakeCoralProjectiles(); + visualizeHeldCoral(); + autoDropNearCS(); + + inputs.positionRots = endEffector.getPosition().getValueAsDouble(); + inputs.velocityRps = endEffector.getVelocity().getValueAsDouble(); + + inputs.appliedVolts = endEffector.getMotorVoltage().getValueAsDouble(); + + inputs.statorCurrent = endEffector.getStatorCurrent().getValueAsDouble() * (hasCoral ? 10.0 : 0.1); + inputs.supplyCurrent = endEffector.getSupplyCurrent().getValueAsDouble(); + + if (inputs.appliedVolts <= -1.0) { + intakeCoralProjectiles(); + } else if (inputs.appliedVolts >= 1.0) { + shootCoral(); + } + } + + @Override + public void setSpeed(double speed) { + endEffector.set(speed); + } + + private void intakeCoralProjectiles() { + // cooldown between shooting and restarting the intake + // so you don't immediately reintake what you just launched + if (shootingTimer.get() > SHOOTING_TIME) { + shootingTimer.stop(); + shootingTimer.reset(); + disableIntake = false; + } else if (shootingTimer.get() > 0) { + disableIntake = true; + } + + if (disableIntake || hasCoral) return; // max 1 coral + + Pose3d intakePose = getEndEffectorPose(); // the end effector is the intake + Set gamePieceProjectiles = + SimulatedArena.getInstance().gamePieceLaunched(); + Set toRemove = new HashSet<>(); + + for (GamePieceProjectile gamePiece : gamePieceProjectiles) { + if (gamePiece instanceof ReefscapeCoralOnFly) { + if (checkCoralPlacement(intakePose.minus(gamePiece.getPose3d()))) { + toRemove.add(gamePiece); + break; // max 1 coral + } + } + } + + for (GamePieceProjectile gamePiece : toRemove) { + gamePieceProjectiles.remove(gamePiece); + intookGamePiecePrevPose = gamePiece.getPose3d(); + hasCoral = true; + intakingTimer.restart(); + break; // max 1 coral + } + } + + private static boolean checkCoralPlacement(Transform3d difference) { + boolean poseWithinTolerance = difference.getTranslation().getNorm() < TRANSLATIONAL_TOLERANCE_METERS + && Math.abs(difference.getRotation().getX()) < ROTATIONAL_TOLERANCE_RADIANS + && Math.abs(difference.getRotation().getY()) < ROTATIONAL_TOLERANCE_RADIANS + && Math.abs(difference.getRotation().getZ()) < ROTATIONAL_TOLERANCE_RADIANS; + return poseWithinTolerance; + } + + private void visualizeHeldCoral() { + Logger.recordOutput("FieldSimulation/Pose", new Pose3d(poseSupplier.get())); + + if (intakingTimer.isRunning()) { + if (intakingTimer.get() > INTAKING_TIME) { + intakingTimer.stop(); + intakingTimer.reset(); + } + Logger.recordOutput( + "FieldSimulation/Held Coral", + intookGamePiecePrevPose.interpolate(getEndEffectorPose(), intakingTimer.get() / INTAKING_TIME)); + } else if (hasCoral) { + Logger.recordOutput("FieldSimulation/Held Coral", getEndEffectorPose()); + } else { + Logger.recordOutput("FieldSimulation/Held Coral", Pose3d.kZero); + } + } + + private Transform3d getEndEffectorTransform() { + // not entirely working + return new Transform3d( + new Translation3d(SimulationConstants.PIVOT_TO_MIDDLE_OF_CORAL_RADIUS, 0, 0) // EE is 12in from pivot + .rotateBy(new Rotation3d( + 0, + -armAngleSupplier.getAsDouble() + - SimulationConstants.PIVOT_TO_MIDDLE_OF_CORAL_ANG_OFFSET, + 0)) // rotate around pivot + .plus(new Translation3d( + 0, + 0, + elevatorHeightSupplier.getAsDouble() + + AlignConstants.ELEVATOR_STARTING_HEIGHT)), // robot to pivot translation + new Rotation3d( + 0, + -Math.PI - armAngleSupplier.getAsDouble() - SimulationConstants.PIVOT_ANGLE_TO_CORAL_ANGLE, + 0)); // constant rotation + } + + private Pose3d getEndEffectorPose() { + Pose3d robotPose = new Pose3d(poseSupplier.get()); + return robotPose.transformBy(getEndEffectorTransform()); + } + + private void shootCoral() { + if (!hasCoral) return; + // if (shootingTimer.get() > 0) return; + + Transform3d eeTransform = getEndEffectorTransform(); + + SimulatedArena.getInstance() + .addGamePieceProjectile(new ReefscapeCoralOnFly( + // Obtain robot position from drive simulation + poseSupplier.get().getTranslation(), + // The scoring mechanism is installed at this position on the robot + eeTransform.getTranslation().toTranslation2d(), + // Obtain robot speed from drive simulation + chassisSpeedsSupplier.get(), + // Obtain robot facing from drive simulation + poseSupplier.get().getRotation(), + // The height at which the coral is ejected + eeTransform.getMeasureZ(), + // The initial speed of the coral + MetersPerSecond.of(-2), + // The coral is ejected at this angle + eeTransform.getRotation().getMeasureAngle().unaryMinus())); + + hasCoral = false; + disableIntake = true; + shootingTimer.restart(); + } + + private void autoDropNearCS() { + if (hasCoral) { + return; + } + + ChassisSpeeds speeds = chassisSpeedsSupplier.get(); + if (Math.abs(speeds.vxMetersPerSecond + speeds.vyMetersPerSecond + speeds.omegaRadiansPerSecond) > 0.1) { + return; + } + + Pose2d robotPose = poseSupplier.get(); + Pose2d nearestCS = robotPose.nearest(FieldConstants.CORAL_STATIONS); + Transform2d diff = robotPose.minus(nearestCS); + + if (diff.getTranslation().getNorm() > TRANSLATIONAL_TOLERANCE_METERS * 2) return; + + if (droppingTimer.get() > DROP_COOLDOWN) { + droppingTimer.stop(); + droppingTimer.reset(); + } else if (droppingTimer.get() > 0) { + return; + } + + droppingTimer.restart(); + System.out.println("drop"); + + SimulatedArena.getInstance() + .addGamePieceProjectile(new ReefscapeCoralOnFly( + // Obtain robot position from drive simulation + nearestCS.getTranslation(), + // The scoring mechanism is installed at this position on the robot + Translation2d.kZero, + // Obtain robot speed from drive simulation + new ChassisSpeeds(), + // Obtain robot facing from drive simulation + nearestCS.getRotation().plus(Rotation2d.k180deg), + // The height at which the coral is ejected + Meters.of(1), + // The initial speed of the coral + MetersPerSecond.of(1), + // The coral is ejected at this angle + Degrees.of(-55))); + } +} diff --git a/src/main/java/frc/robot/util/simulation/MapleSimSwerveDrivetrain.java b/src/main/java/frc/robot/util/simulation/MapleSimSwerveDrivetrain.java new file mode 100644 index 0000000..320b7ea --- /dev/null +++ b/src/main/java/frc/robot/util/simulation/MapleSimSwerveDrivetrain.java @@ -0,0 +1,269 @@ +package frc.robot.util.simulation; + +// Copyright 2021-2025 Iron Maple 5516 +// Original Source: +// https://github.com/Shenzhen-Robotics-Alliance/maple-sim/blob/main/templates/CTRE%20Swerve%20with%20maple-sim/src/main/java/frc/robot/utils/simulation/MapleSimSwerveDrivetrain.java +// +// This code is licensed under MIT license (see https://mit-license.org/) + +import static edu.wpi.first.units.Units.*; + +import com.ctre.phoenix6.configs.CANcoderConfiguration; +import com.ctre.phoenix6.configs.Slot0Configs; +import com.ctre.phoenix6.configs.TalonFXConfiguration; +import com.ctre.phoenix6.hardware.CANcoder; +import com.ctre.phoenix6.hardware.Pigeon2; +import com.ctre.phoenix6.hardware.TalonFX; +import com.ctre.phoenix6.signals.StaticFeedforwardSignValue; +import com.ctre.phoenix6.sim.CANcoderSimState; +import com.ctre.phoenix6.sim.Pigeon2SimState; +import com.ctre.phoenix6.sim.TalonFXSimState; +import com.ctre.phoenix6.swerve.SwerveDrivetrain; +import com.ctre.phoenix6.swerve.SwerveModule; +import com.ctre.phoenix6.swerve.SwerveModuleConstants; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.math.system.plant.DCMotor; +import edu.wpi.first.units.measure.*; +import edu.wpi.first.wpilibj.RobotBase; +import org.ironmaple.simulation.SimulatedArena; +import org.ironmaple.simulation.drivesims.COTS; +import org.ironmaple.simulation.drivesims.SwerveDriveSimulation; +import org.ironmaple.simulation.drivesims.SwerveModuleSimulation; +import org.ironmaple.simulation.drivesims.configs.DriveTrainSimulationConfig; +import org.ironmaple.simulation.drivesims.configs.SwerveModuleSimulationConfig; +import org.ironmaple.simulation.motorsims.SimulatedBattery; +import org.ironmaple.simulation.motorsims.SimulatedMotorController; + +/** + * + * + *

Injects Maple-Sim simulation data into a CTRE swerve drivetrain.

+ * + *

This class retrieves simulation data from Maple-Sim and injects it into the CTRE + * {@link com.ctre.phoenix6.swerve.SwerveDrivetrain} instance. + * + *

It replaces the {@link com.ctre.phoenix6.swerve.SimSwerveDrivetrain} class. + */ +public class MapleSimSwerveDrivetrain { + private final Pigeon2SimState pigeonSim; + private final SimSwerveModule[] simModules; + public static SwerveDriveSimulation mapleSimDrive; + + /** + * + * + *

Constructs a drivetrain simulation using the specified parameters.

+ * + * @param simPeriod the time period of the simulation + * @param robotMassWithBumpers the total mass of the robot, including bumpers + * @param bumperLengthX the length of the bumper along the X-axis (influences the collision space of the robot) + * @param bumperWidthY the width of the bumper along the Y-axis (influences the collision space of the robot) + * @param driveMotorModel the {@link DCMotor} model for the drive motor, typically DCMotor.getKrakenX60Foc() + * + * @param steerMotorModel the {@link DCMotor} model for the steer motor, typically DCMotor.getKrakenX60Foc() + * + * @param wheelCOF the coefficient of friction of the drive wheels + * @param moduleLocations the locations of the swerve modules on the robot, in the order FL, FR, BL, BR + * @param pigeon the {@link Pigeon2} IMU used in the drivetrain + * @param modules the {@link SwerveModule}s, typically obtained via {@link SwerveDrivetrain#getModules()} + * @param moduleConstants the constants for the swerve modules + */ + public MapleSimSwerveDrivetrain( + Time simPeriod, + Mass robotMassWithBumpers, + Distance bumperLengthX, + Distance bumperWidthY, + DCMotor driveMotorModel, + DCMotor steerMotorModel, + double wheelCOF, + Translation2d[] moduleLocations, + Pigeon2 pigeon, + SwerveModule[] modules, + SwerveModuleConstants... + moduleConstants) { + this.pigeonSim = pigeon.getSimState(); + simModules = new SimSwerveModule[moduleConstants.length]; + DriveTrainSimulationConfig simulationConfig = DriveTrainSimulationConfig.Default() + .withRobotMass(robotMassWithBumpers) + .withBumperSize(bumperLengthX, bumperWidthY) + .withGyro(COTS.ofPigeon2()) + .withCustomModuleTranslations(moduleLocations) + .withSwerveModule(new SwerveModuleSimulationConfig( + driveMotorModel, + steerMotorModel, + moduleConstants[0].DriveMotorGearRatio, + moduleConstants[0].SteerMotorGearRatio, + Volts.of(moduleConstants[0].DriveFrictionVoltage), + Volts.of(moduleConstants[0].SteerFrictionVoltage), + Meters.of(moduleConstants[0].WheelRadius), + KilogramSquareMeters.of(moduleConstants[0].SteerInertia), + wheelCOF)); + mapleSimDrive = new SwerveDriveSimulation(simulationConfig, new Pose2d()); + + SwerveModuleSimulation[] moduleSimulations = mapleSimDrive.getModules(); + for (int i = 0; i < this.simModules.length; i++) + simModules[i] = new SimSwerveModule(moduleConstants[0], moduleSimulations[i], modules[i]); + + SimulatedArena.overrideSimulationTimings(simPeriod, 1); + SimulatedArena.getInstance().addDriveTrainSimulation(mapleSimDrive); + } + + /** + * + * + *

Update the simulation.

+ * + *

Updates the Maple-Sim simulation and injects the results into the simulated CTRE devices, including motors and + * the IMU. + */ + public void update() { + SimulatedArena.getInstance().simulationPeriodic(); + pigeonSim.setRawYaw( + mapleSimDrive.getSimulatedDriveTrainPose().getRotation().getMeasure()); + pigeonSim.setAngularVelocityZ(RadiansPerSecond.of( + mapleSimDrive.getDriveTrainSimulatedChassisSpeedsRobotRelative().omegaRadiansPerSecond)); + } + + /** + * + * + *

Represents the simulation of a single {@link SwerveModule}.

+ */ + protected static class SimSwerveModule { + public final SwerveModuleConstants + moduleConstant; + public final SwerveModuleSimulation moduleSimulation; + + public SimSwerveModule( + SwerveModuleConstants moduleConstant, + SwerveModuleSimulation moduleSimulation, + SwerveModule module) { + this.moduleConstant = moduleConstant; + this.moduleSimulation = moduleSimulation; + moduleSimulation.useDriveMotorController(new TalonFXMotorControllerSim(module.getDriveMotor())); + moduleSimulation.useSteerMotorController( + new TalonFXMotorControllerWithRemoteCanCoderSim(module.getSteerMotor(), module.getEncoder())); + } + } + + // Static utils classes + public static class TalonFXMotorControllerSim implements SimulatedMotorController { + public final int id; + + private final TalonFXSimState talonFXSimState; + + public TalonFXMotorControllerSim(TalonFX talonFX) { + this.id = talonFX.getDeviceID(); + this.talonFXSimState = talonFX.getSimState(); + } + + @Override + public Voltage updateControlSignal( + Angle mechanismAngle, + AngularVelocity mechanismVelocity, + Angle encoderAngle, + AngularVelocity encoderVelocity) { + talonFXSimState.setRawRotorPosition(encoderAngle); + talonFXSimState.setRotorVelocity(encoderVelocity); + talonFXSimState.setSupplyVoltage(SimulatedBattery.getBatteryVoltage()); + + return talonFXSimState.getMotorVoltageMeasure(); + } + } + + public static class TalonFXMotorControllerWithRemoteCanCoderSim extends TalonFXMotorControllerSim { + private final int encoderId; + private final CANcoderSimState remoteCancoderSimState; + + public TalonFXMotorControllerWithRemoteCanCoderSim(TalonFX talonFX, CANcoder cancoder) { + super(talonFX); + this.remoteCancoderSimState = cancoder.getSimState(); + + this.encoderId = cancoder.getDeviceID(); + } + + @Override + public Voltage updateControlSignal( + Angle mechanismAngle, + AngularVelocity mechanismVelocity, + Angle encoderAngle, + AngularVelocity encoderVelocity) { + remoteCancoderSimState.setSupplyVoltage(SimulatedBattery.getBatteryVoltage()); + remoteCancoderSimState.setRawPosition(mechanismAngle); + remoteCancoderSimState.setVelocity(mechanismVelocity); + + return super.updateControlSignal(mechanismAngle, mechanismVelocity, encoderAngle, encoderVelocity); + } + } + + /** + * + * + *

Regulates all {@link SwerveModuleConstants} for a drivetrain simulation.

+ * + *

This method processes an array of {@link SwerveModuleConstants} to apply necessary adjustments for simulation + * purposes, ensuring compatibility and avoiding known bugs. + * + * @see #regulateModuleConstantForSimulation(SwerveModuleConstants) + */ + public static SwerveModuleConstants[] regulateModuleConstantsForSimulation( + SwerveModuleConstants[] moduleConstants) { + for (SwerveModuleConstants moduleConstant : moduleConstants) + regulateModuleConstantForSimulation(moduleConstant); + + return moduleConstants; + } + + /** + * + * + *

Regulates the {@link SwerveModuleConstants} for a single module.

+ * + *

This method applies specific adjustments to the {@link SwerveModuleConstants} for simulation purposes. These + * changes have no effect on real robot operations and address known simulation bugs: + * + *

    + *
  • Inverted Drive Motors: Prevents drive PID issues caused by inverted configurations. + *
  • Non-zero CanCoder Offsets: Fixes potential module state optimization issues. + *
  • Steer Motor PID: Adjusts PID values tuned for real robots to improve simulation + * performance. + *
+ * + *

Note:This function is skipped when running on a real robot, ensuring no impact on constants used on real + * robot hardware.

+ */ + private static void regulateModuleConstantForSimulation(SwerveModuleConstants moduleConstants) { + // Skip regulation if running on a real robot + if (RobotBase.isReal()) return; + + // Apply simulation-specific adjustments to module constants + moduleConstants + // Disable encoder offsets + .withEncoderOffset(0) + // Disable motor inversions for drive and steer motors + .withDriveMotorInverted(false) + .withSteerMotorInverted(false) + // Disable CanCoder inversion + .withEncoderInverted(false) + // Adjust steer motor PID gains for simulation + .withSteerMotorGains(new Slot0Configs() + .withKP(70) + .withKI(0) + .withKD(4.5) + .withKS(0) + .withKV(1.91) + .withKA(0) + .withStaticFeedforwardSign(StaticFeedforwardSignValue.UseClosedLoopSign)) + .withSteerMotorGearRatio(16.0) + // Adjust friction voltages + .withDriveFrictionVoltage(Volts.of(0.1)) + .withSteerFrictionVoltage(Volts.of(0.05)) + // Adjust steer inertia + .withSteerInertia(KilogramSquareMeters.of(0.05)); + } + + public static Pose2d getSimulatedPose() { + return mapleSimDrive.getSimulatedDriveTrainPose(); + } +} From 3c61b001cdca94c6f46415ea3c3369ec661e574f Mon Sep 17 00:00:00 2001 From: nh17000 <46301909+nh17000@users.noreply.github.com> Date: Sun, 11 May 2025 15:51:41 -0500 Subject: [PATCH 04/58] Upload CAD, start vision, adjust l3 + alignment TODO: use PV sim, simulate algae, hardware abstract climber + drive --- .gitignore | 4 +- ascope_assets/Robot_Pearracuda/config.json | 166 ++++++++++++++++ ascope_assets/Robot_Pearracuda/model.glb | Bin 0 -> 25020668 bytes ascope_assets/Robot_Pearracuda/model_0.glb | Bin 0 -> 13047012 bytes ascope_assets/Robot_Pearracuda/model_1.glb | Bin 0 -> 4860272 bytes ascope_assets/Robot_Pearracuda/model_2.glb | Bin 0 -> 1242796 bytes simgui-window.json | 18 +- simgui.json | 1 + src/main/java/frc/robot/Constants.java | 9 +- src/main/java/frc/robot/RobotContainer.java | 13 +- .../java/frc/robot/commands/AutoAlign.java | 13 +- .../java/frc/robot/subsystems/Arm/Arm.java | 5 + .../subsystems/CommandSwerveDrivetrain.java | 6 +- .../subsystems/Elevator/MechVisualizer.java | 106 ++++------- .../EndEffector/EndEffectorIOSim.java | 58 +++--- .../frc/robot/subsystems/Vision/Vision.java | 179 ++++++++++++++++++ .../subsystems/Vision/VisionConstants.java | 55 ++++++ .../frc/robot/subsystems/Vision/VisionIO.java | 49 +++++ .../subsystems/Vision/VisionIOLimelight.java | 150 +++++++++++++++ .../Vision/VisionIOPhotonVision.java | 129 +++++++++++++ .../Vision/VisionIOPhotonVisionSim.java | 59 ++++++ .../subsystems/Vision/VisionIOQuestNav.java | 24 +++ .../Vision/VisionIOQuestNavSim.java | 33 ++++ 23 files changed, 953 insertions(+), 124 deletions(-) create mode 100644 ascope_assets/Robot_Pearracuda/config.json create mode 100644 ascope_assets/Robot_Pearracuda/model.glb create mode 100644 ascope_assets/Robot_Pearracuda/model_0.glb create mode 100644 ascope_assets/Robot_Pearracuda/model_1.glb create mode 100644 ascope_assets/Robot_Pearracuda/model_2.glb create mode 100644 src/main/java/frc/robot/subsystems/Vision/Vision.java create mode 100644 src/main/java/frc/robot/subsystems/Vision/VisionConstants.java create mode 100644 src/main/java/frc/robot/subsystems/Vision/VisionIO.java create mode 100644 src/main/java/frc/robot/subsystems/Vision/VisionIOLimelight.java create mode 100644 src/main/java/frc/robot/subsystems/Vision/VisionIOPhotonVision.java create mode 100644 src/main/java/frc/robot/subsystems/Vision/VisionIOPhotonVisionSim.java create mode 100644 src/main/java/frc/robot/subsystems/Vision/VisionIOQuestNav.java create mode 100644 src/main/java/frc/robot/subsystems/Vision/VisionIOQuestNavSim.java diff --git a/.gitignore b/.gitignore index a5b7765..d012c1d 100644 --- a/.gitignore +++ b/.gitignore @@ -170,8 +170,8 @@ out/ # Simulation GUI and other tools window save file networktables.json -# simgui*.json -# *-window.json +simgui*.json +*-window.json # Simulation data log directory logs/ diff --git a/ascope_assets/Robot_Pearracuda/config.json b/ascope_assets/Robot_Pearracuda/config.json new file mode 100644 index 0000000..1237603 --- /dev/null +++ b/ascope_assets/Robot_Pearracuda/config.json @@ -0,0 +1,166 @@ +{ + "name": "Pearracuda", + "sourceUrl": "https://github.com/Pearadox/2025RobotCode", + "rotations": [ + { + "axis": "x", + "degrees": 90 + }, + { + "axis": "z", + "degrees": 180 + } + ], + "position": [ + 0, + 0, + 0 + ], + "cameras": [ + { + "name": "Northstar 0", + "rotations": [ + { + "axis": "y", + "degrees": -28.125 + }, + { + "axis": "z", + "degrees": 30.0 + } + ], + "position": [ + 0.225425, + 0.2667, + 0.20955 + ], + "resolution": [ + 1600, + 1200 + ], + "fov": 75 + }, + { + "name": "Northstar 1", + "rotations": [ + { + "axis": "y", + "degrees": -16.875 + }, + { + "axis": "z", + "degrees": -4.709 + } + ], + "position": [ + 0.08255, + 0.127, + 0.16256 + ], + "resolution": [ + 1600, + 1200 + ], + "fov": 45 + }, + { + "name": "Northstar 2", + "rotations": [ + { + "axis": "y", + "degrees": -28.125 + }, + { + "axis": "z", + "degrees": -30.0 + } + ], + "position": [ + 0.225425, + -0.2667, + 0.20955 + ], + "resolution": [ + 1600, + 1200 + ], + "fov": 75 + }, + { + "name": "Northstar 3", + "rotations": [ + { + "axis": "y", + "degrees": -33.75 + }, + { + "axis": "z", + "degrees": 176.386 + } + ], + "position": [ + -0.4064, + -0.3048, + 0.2159 + ], + "resolution": [ + 1600, + 1200 + ], + "fov": 90 + } + ], + "components": [ + { + "zeroedRotations": [ + { + "axis": "x", + "degrees": 90 + }, + { + "axis": "z", + "degrees": 180 + } + ], + "zeroedPosition": [ + 0.0, + 0.0, + 0.0 + ] + }, + { + "zeroedRotations": [ + { + "axis": "x", + "degrees": 90 + }, + { + "axis": "z", + "degrees": 180 + } + ], + "zeroedPosition": [ + 0.0, + 0.0, + -1.0023799104 + ] + }, + { + "zeroedRotations": [ + { + "axis": "x", + "degrees": 90 + }, + { + "axis": "z", + "degrees": 180 + } + ], + "zeroedPosition": [ + 0.0, + -0.3429, + -0.2286 + ] + } + ] +} diff --git a/ascope_assets/Robot_Pearracuda/model.glb b/ascope_assets/Robot_Pearracuda/model.glb new file mode 100644 index 0000000000000000000000000000000000000000..36595cb2710efb14a4f75474386cb1175292b487 GIT binary patch literal 25020668 zcmeFa>yjMDnfJH0Z=?hMLWO5WUFT}r;Rq0{NnA~>zlWaKKe7$Z@9=$&QD+{g9)>YY5 zo2uAkRk3dBB0u5Ty4e&><^HSKguiXt|KzK$uK4Qd&Ubl<9(G^We->p{WO=pjesaEi z>vr_$cV9dy9{v4f_8?hVt~YMu`%jZM4afI~;f;A-=#<|&Gm6dH)hsVk{Rlcs;lAUMGMr-IhS+%JP?!tekN<2!_6h-7H_4XjVtghVV z*KA&JD2h!p+#>)C_uGG1yVU1Xx7Mz!$ky_*yS>qM?l2`U^Qsvhu08tj z$!0VBG~vG2yXy#Pb{Eo9eRjN30xsq2rWD%GQN|`OgF_argFu$IO%oi};R6rBnXEr; zt}FLc(ILxv_iH+Y{a&?6B#1m~%NRjq`6j@lb-6CuD!6}Pa}HJZTj$@L8ia#v%DSv; zLka7=&fCrKS+GFIa7d~DsOxppZm(foq+wnztd3w_2Au{#shYBdzqD=LlueU4X4Rb~ z+pw9sEF9GG8U)qnnsU=*nKl-1t#A=I-j>8U?)GbKz9}8IOF^=-E?Txbhh%vO9d{g9 zFIy}tj_Q$XT?$|vE30ZaQSR)ExZzvN%28M`A?&XAQyR~c!w6qfz_M%d0tgPEQa>CNUa1(O9b=iuB%pR6n=R6bTI@0&i1~OGeQ-UoOakLTNs2O#V&EKlW0Uix z;CfFo*gymOtE+}X7tOj5!J`bJ3RNX+psjN-(VVYsq@L++0BDnK{KtxQhN#q+>vb#6 z)GfG9gd2MS1Lom|5DmbFG77%4`wY32WsPTuYbiKeTw`+%n(MNu1C^*8WUvFs?n>_Q z?o#gY#9Arf%Zn;TQMtj-H8G$LXiOmvp8^ylj@} z@;cB8v&tzFXc1BfxmApgqO3Q_QIHk-FsRpmx`4O&PZu@JC2!VfMNLt+iGm5HkCH#X z-8usqx28gtH(WX>zd^%hy9GbZz|z*{p1bXCxRUj2c=sSfSypd z+#~|s3y3wQO0Z{785xQLB)>s*;(x`6r|queC}3wHJsqv&l*5Em!i_MlB0wo+n+{O% zSR{Vf;YHTMmqQ-w*c#tMts&xyWo8M&FY?^+PybVm*R80n=BV*v3 zj(96{Eze4!=NhGs|Ei=1@M({T7So|H< zxIvRHb7|`ir%+OnWfkkd;el=36%!BVRD^y>EP~YXyV%m@RB_#89%4yG(~`hYk;RsOL*;^q#EGk_O|b{-7nLC zz*ePG&2BYYV^|IB3j-V@1iqAKRq0d{=m4_T#yK{apNSu@Gd_mBov$JKd>|d2bA#E6 z7=^2}D0P`v$Lbp78W!;==GK6)5n*|ji)Ez10UuIKnr9)|WE*_}nnv15@$yjm0bHl*0#E}^&iNApj{r9T3S^8Iw9QIbhr4(57Q7!FN6!7m#2u;(%!V=J z3FQAF0NF8*stogOjhTUj-oH>&R~7yi7~#6DSSb}n*;@pLTd4{Xq6PLZPtHn@!)1jow=s8CZFCiN?JBsVeWjN44c58s`p^H{80v@DL&~ zwsOup#8K9_vXKAi9TrkG(R5(Ay0AnnZNz^gSQ?l`Tgz^VQ0T-+ZlgKbdQOXMk0w=XH7of(^0n@QhE|MG}M-wgMZPM<{D+XKTP*r2@iFRCN94s>gn)(~ae{#S`M(>i^|lcO=3!_XRxS|K{!s{hUwpAyv_;#^U8AZup< z8K8KgaSizE6l(Vn5#Rl|XGGSBc?`O#L7d%H9Exb|a2a<(x6by2F8q}Mn+^WhScnUn zhE;7tTu!mZf6*UD|1Q0aFnVesgl94QidO;f4i0;V+P(VAQ?tAlN;y<6jdPyjQM7_H zVeH|`b6}IN)0?dhjkeD^2SWHkXo-os_~H;SP>G91CcHz{U>+wPfw8WY%Sqk%)kCGU= zcL@Vx0D8H>KfTXIpJ}Ab=sC*&Nq*-1FY66~`BF>?in8e~JL~8?q#NW7ZeIk4|Et`7 z+n+>IRJ;T~(){W0fc1o^_v6NOkq-`u9|(7bKN4==PFayhQ~r1Sig?ga;H)19gN#@- zM)HPq6r3UM7$lvr5Ggh#tPdZUdx%IKFopk0)Tr5JL9Ao`aLV@x`5^d-0$HsI>fq<_ z`f-jybJ+zoSTw34H^%q~Yn@QDDKVr0CqGe%@C92K6W7yuwSW@w4Rf7t}(J#!uv`VC1U&$<}+pb z1ZQ$;4g69$Go9_?Lr`Ng$Xd&?gSa0YhNRbQO(osV9StE}trY%Qb(e50pdIXlhV2xU z7$4B^#y$e5Y~cpPt;qV4;1F$&d=upm=n#VP9lK8VaI}!a<*AiY6gWl3W0@TagZ0Pc zrJ#~a>cnF%)gCQ|kQ5e+ekGI)(g{q2m-qputj@nRL!b_V9iRq+5|buT77#iod^Hau z0(b$4dc|G}m^V0ZzVAtZ*qRB$cGJ@za7v@k#uSiEv$almYl-|l#EIejHP(xf92+9M zh%k%rD`>Pw2O%@sD(b@a$5FDw^6@W>a z@CW>!vE1GJ$?X8h2qD6lgDr3QYZ7B-&mBJ>_}tytGKo>hfCz5be9avx=JgvQ;aCoc zD7X^NW^bU7K1JBDMp*}cvTDE^c#-=WYPy6__chWg{9@G4Y^W0=;{gtn?A-;Kadt!) zxxsj(Jc1v8AQFzKenrNxxTOtNU{UZ?D%qBQ>OU-}H0xj`y7P<|@&s>+Y4AZLGRj)a zH{yGQ_(JxNUm{Q)NmbJ+M-ROcixq)G!ePAl?MRn$hM89%@` z`Is9lr3e{Dj;T|kLzEjNuir(V-Yc&N6)FDg3m{1f9w6*5g`4qrg((Id;3;w^PllxM zJi<_8$m#&FrYMi7UPnrZKfgQWbwXMS1A>Fvo%iPK1tj{3*rq4!tnLm8p5UbbQ}Eac zb5j9{voID>6Cwr-l?1q5exZm7`7!JO_M>~#(eZ35CmFd{VqCX_NvYovK@GW1CmIPE z$YrkR3b|-oK$2CaEEGM&xtVxIawKpJ-3?hiO{!i4%yb+EYVv>-U|Upv&qwSb$E?*Y zgF1sJwC6Bgv{Ak$`Sl%BD_n|bik3`nFdnY?GZG{Zz(}eo>EMGK&>4R~5NX~>I+rel z?cqp9CVBlBVk`lG3~wcwze3gDY7(7G4r59z$}dEIms<#ai-Q^&;FeF$?xd=K%(**4 zQf!9=Ja*7?hAyF>kP0y%Yz_Tjkj+x0Rzc54PV{UFLEPa3j$AHJCYQ=0f3ldx z8{<3L9a-TxFcH(RdW1%&d&(zDJ|G$A=;EYMFW@_1Ho@N>G0`nNPAF4bG_1UXk}RTB zqC~rhW$ECE3p3?=jP0vDJ58=8;}<=flt<_)@4{|S7zBznfvpR}vJn9g01JAnI8hAk zjzp~=`4|0CsHYwKk)-6xx;G>rl&t=kV!i~Ppr&g7I=zIe6EA^X%0vOoBu`Oa62)1} zG4*cfl%y`<3axBx{6#P9ea zxIjqLd26s!aQHazt45R76#Y_NtQn=n6}@zKlBe<>l5L6D%u^*wc6dx&2;ddfcjP{F znd+!LxN*>j{4>8{$73>v8W?atTT)8P9mPYPa;j%hSBh?RZdhV5Y>6hV`K zg7M7qe^|axUqIGN8tPQCm*llp6)E9r+7njPF1)-80a&p^n_s& z(^d#+hMWU_BLc?kl(d@jUL#G*;Q zVGRIDdDd_*&gX%O>10{=I5FW(RkqQb6B3MUnsoepPMy-$W{%`CJ7BJ%!@}#%^vMa& zE=wu}W@zIu_IcbCjJ9HW7iOqyJ1}!Hm#qb12_j*02NVmg@Ob&)t4hKXPXg{y{WgCR z%Jq8OgUWnh+93lf#zgsyFq3VKKUfUjYf+O~1_j0iBAm{#^P99Ifvad>kt5;E2#z%B zx3lp<5z&XvG3FqKh~OP?9MtHpSC2PZ;Kqiwe4&V6DIl*zVa8?03;$40!=vFP<_ri> zeKr`-P-rJ$C%<5V3C(J~F@Mz|i_tqh8=2xU`mN_c zhcg*$MFIiyI~r5q6h8^sLuZUBRo?x0UbMYt$2h{zJEpYr)bTI(RGmOaE2WSp?q*o~ z{1IKn_f`SyZk2rlf4q2>JE}E>YY63%qxb;Z<8Vn^q9!87_gp^eHa|hh5fC8|Cw@R$ z-0;)gwthW4w4B3#dHAh&mbn&+{(|{(pz$W31_xCv6@e&KD5w-O@F53vgYJ?o^vq(3 z2`%6@@$A}v#qHd!lY04x)tEhpQ5*`^F2CAc|A39|LI({Q*tq>UbRRCe3uWP6h3nug z15T7&B-YtkQ*X zaEcKi+V&>%PpP_4RtiVgGO1l(c}X2jN5X*G7Voe(VyI+OBRol7t~iwgP{6*oJY0QZ z{0V*4zd+EVssB)|b(s5vEma|c>vwcJg(`M4GCB@y!|Rl{)^0ivYT zkZ}d+;{G8xN_d$NWaoZF))Vo=$f8g{4R_qZ3AXJ&BkRynO&!UpkiviDDG9GT-gum8 zM2ku;(IE)TCAg|YlLytGoXrTg^#Xm%+wfYGr+}*$SW=^-O{hgJF;O)^B4Wd}`JK%I z5!zDgYJ8b+$j&7`)ohNSozfV4G)<*MwXKWAu7=KCqM%VLtv(Zzi0{yet1mI5dT>lb zgXd(_*~{akZ48D(!ei?0Iw=Cm;Yvg?SBgb|sZbH78Yqc^)pmVv)qRT4IW1M#I^_`# zwDP@D97fRydKC8Ym=+y}q+meB-CJ6OZ6Pv6jnHW)zm#4vz%i8=30{H-^TbHVCKLl? z;SyA(m`Q~i_+TBXib;U<^0~uC;W$eUNm2wM5Bk@T`lTE<$7qRW;)c~B;jK7<-BS`= zAaIZst%KyJ)KjvfXcqF;_XV!X2v$l1{TB)9qj>wk3%N8h)Je;1$>H@e5K;vBJ@G_J zj$oRDCuMgTiha8yLfLQ}6f$y|DC^Znkwa?erbH4B?!4J4sLBbUqj@-n#sTM};V=z^n)IA&CK2%WcF6_t#=_1)hjIfP^|$%*!H=rrO|JxdJF zs4KGF==?ep-RyQ(NrWROoQLC9GU_O{{~ML8o{SXX-)$hbySIU@f`MT>I#Mm&O__Ff zXMXUIR$I@j6b9FINTDb4CFV%1yV7Um&XoC)Gj>a zxX+#A3!^r9SQt78w-9oDkx>9i0`;6|XuRjXLhfYPx353^#7b$fADTgL6&iSG{ zpZwHAGOC6 zP%UN9;ur7LE;4K!XYg(T*E%KOq=E}x2SgxFEcs@2PL_g|RN~0g^!7#w@faRECXZF3{sr*um~uF za|)xTH!?bW?3lU)^A$1DiL-aKs-BQaLpzj{a!!H-5z&vICDh{_>F`oiEo@eGhtcUJ z;l>YD&9O%+>YO4>!lAgkXtB^GVT_**z&uzaBDzugBWJ{m9m>QoK|;LK@tH8cO~mFU z|2)ceV-`qv4Ec4pAWt~>aNutXdv(!?WbNt@U@hcHbwb)c^WN+& z>^#RGx#8_Ho)kxG<2rMQdoZsd!#CRCG9ni}+{VJvA(fG67_x&hqhF6iV`rC4E@VV3 z1z3r0Myd%Nx1JAL4jP-=ykQY|4IByXFdz}x7Cpx*n}dz{iuYmIrCV=D-I>o&$w#a4 zdAWgxA0|es^$4!)l8iAW6jqLPjvkU<=k5bdAQX*5B*UH3E(BYjc*^pArC!K7^*gn5 zF19A6dl9*Tm9bR;+&dl9V~PVs^Ej&TYx}L($4)-Z5~bH^G*JPT%9Z(JI@4qH(1Y`E zj!JlrSj9XvWeoHht2-s60Y#&o;437@oEC!qF|H?~$tc;1!t`0m{Xsj$)e@&F@G%RO z`mfyBPUh?QI6AN#NiIO;>%3vTPA87dPn&3KP^QzsWg}(K$(B2-bmsgc^8OhIJIG z@T+$!4|JNSyJ}uwj0b^+TOQP7EzK!#my%n+NnJLc({|9HQMT1Z0FF5iNp~1<7Sa|0 z;4SfA5JI?i7|d@#igW~VSA>N!qPEt&*zAHEox@xMO$OVKOR(JaU`d&pYJeR?L0^Ot zaTkVqoVrtp=!x4vjFbWjP@{((R&^4jBc74}#wlE+W;REs-|0nw2~+jj4%{03&@ z>cwVrm}a$A?+pkNoOJ`3<8!C69lD*q4|I+ z#cg6gl*eP_5stK$RkuN_+l)uJLkYd=MEak^cu+|C(L{oLNWaiB>hh_MKX|&(i%EWR&_&_WpaV6p!ouzHp(#|r-ep-rThM-@ ziivZFRJnONiXG8iJ7o^TKHx%~Bhj2Z0NeB-wbJNfh@0rM_UNhQ)pB`7i$a29x)WI# zc(H`03Bjm_1{0m)3=acp1cQf6+q2j?!U-=YIVR@O7Q&q+WLHWa+`u_$z#d_XD1RY^ z5x_UR&LJoHX*h$SIdp3E#oB#{^}Ri%00cS*e4c)AUa8z!$br~A^(!TCOZDF)k#I56 z?uVu_q{x&)1>unD*Qk@A2My39^?rLyx6TwWfh0*%&^)P=gnT^Jvk0k_Bni5f!T2ZB zC{vLmY5?XB8B|<%n**b^*x7-NX|;%5&`tkDggaP{9*!hAsbW2k*T1(x;L$=3mUgA& zLt>Ofl+Jm&?0KW19GcU3^czvxz+|Uj*#+~>N@SvT=Fy1qlMhNJ-Ex!_9$HKz7sG2B zJ-lR$UlgeIHeFNTQa4?uAsiiC{Q{xqPew-#01R!B3@xajPW8kEtB9qkM z6LFKyYSk+%g0}$+avK>j56@OPWRJDrE}0Y#am_ zlH+Ck$?elbZIrAZBu|7S$w@>x3LG=WFzCI8&S=0a5aDeZ=O7+E#PLuJJhcyXdp0%x zYGT$U8M!Ei5t56cC3hccUT6~icyXh8acL2xbhu!Y!LI8n@yI|8&WptKHcpABAcB*@ zDRt{3#@BiD5ZCe@qTI_Z)G3%o>Z8eQPwCdNyqH3L2UDXy;5v8egFNI^Xsa?9%ionb zr06!J;i(;R#0`VU^hoJ;=gu)0*@y%|(+cKExo;1Nu7i7(%y-xljHBnIJL|Z!+ovp) zc1SgSoYA46CzWHiz~y~^HxjTFkMj`diz(C_9^~ZI1_n}d(W6>f|a6*05pHdBL1}zv< zJdrk;d@plvmdh?vQoS<=o*(|$z&5$2Jud~9!=Fx99X(CeN@=)yMEsVMa}ROkbNP!Ty+*b<$YDaV5hY@fD*+fe5K^QgDGs#boj+*6XLR3_{x}(m%F@KrqYHn}>FvWI z^y|Pj?T_18NOw!6saZbNS|qZJ#W;V;z*VK~8C?^*snb}EVYt9r+|_*Dd3Massi(D$aq44qS0wakc=y;r~xYid^p8b-vs0|#)NJfVY_-3AH&omOC2#-RCV zAxo8m?>OXQl$g4O#z#*EB*y%m)Pml~G8iRQLx3?z3@&bo(p}9IO1N~#tuu$N#||Y7 z5;w^-$=+hZ(v7hS96aa*VQ|euO)XAnutBOA|0gfsosp5pa9%7pyie--W6wy|)7C$U zz2bevNPlLOkQRkOr8==La>v(c{Y26Xs}pKS)(Kqe+7z9DiMqra+zqRXZ*X9rJ?ejN z4%B_+v^i6~D*a{HJp{PUFHSpF>_0KsW~os)GRLFPDu~pfu=ieK_4VWweYZFMw%xPu z>#1M*B7?34Xo^Nj=$XWU`Fow;P-~E)->qw^mcAc#-lf)Uen0GZxE|@$Arkse>VGb z$J8gc`J0_86Xc6CDIw^!*CkT#Ij4Im*p_s*4P|2yR|rGwf}^<>yaNdRgmmaH?7Zvu zNz`tO`(9%(jobT%>pNf7XZ?56PNFiAc_{gWo*qi7oDs+AXq8k4b!*%H3>poD>!}*J z!b8QRm?x6xTcb%6|BqZXrKB8T&jx8Hx*2>+yPLvwpW3b-w;^&Qwkbji+dZkl8gXIu zK2^YgyTD-JHW=GV^%Tt#9m&!8D(KG070a^4rBBByT9C*asOt01FGedCdAL}?|UF0zz@kJ!6P0+!hloIe+H$>W1(8Q420#b)?Lze zlYpG8{r=-5ZgH`$OMD{HGuAmyDi-MYYw0aUdI4434t%PxBklmgl0HE0@E)+M<^!y! z#?Bp*VrF(~3X%4i*e13Yw;Gxfa`KESm^d6U{g zY(*-p6_Y0*VDI6j-6z>W!;jk>f>hlV`yW>nIH-%$3+>*HE`Uyyq`(Y6si31$A=Xie zu)}ajin3`qr%tpGG`fPjaC({fHtQ3+89Xh-5(D!99xGI2zHR3~;+kl*sX_~+QJv@u zq&!#^#t{+`W9YRqDvZ%%hKuvg56hrCmv+sd(jHX&+Y-~{GL%jRU+7$Iw1M7PCkZ3z zeH9y#LWQTA)bxk!#bK{2X;z%kJ<*{Y7@R^3KJ_0+*cbJG=t~jh(~guM&HtDjE9CP) z#8`(73*mRayL}pHU0zD++W{+1^huJ{kKGo-DK#(N-ZwlAtO{P~omR$PMBUPrf0$tA-^M<4oI3^e-Lg@)uvXrU7!;4J>qwPE-f*8B&ArL8{^d+A(7+QpxPfx z3}(tjdX7xqhSx_(!chxwerUMUSX178k-RI4RMnr#eUtIvc=$uUC>)c9MD{X@4Mt<~ z1aZ!UUKOJx@@0F#@J2Wls@(Qaj!mgoh(8qq2vNJ|RQe{77Jn+|nsR97zT*TmzBT@r zCMrqR7VDXpFs}Z~6Nzq3B3lDTy8G>#V}YUcuG#+hI1KHnB>VWV+nlR37&HRfn$V@5 z{-F*~zK8N2Kw+K}twxHfgdjB&j6>?u=MM?V0Lm>Z(7a&)Og{;=8FVW104HKs^5=-i z{3P%2Odu4jlA}?F<1;u}L*=OsPGgHUj0C07;738lbHebi9L?n0twHB6J)!TT(>-_hww3?R{_$oS@fZd~ z3_o2+Y2s#5Ktl{2wQ2rja(xUM07V;AUxN}zZ*IC%*Ud-Q2`sCK%}DjS}9VGgGCpFVu$YvU$%z&FgHYu2Ahi7Ty%p%2%PA3qeux~b>w`g zl;(i2adM_0IsfByW1Jv3O;PI5@STIk?Tj<@pW@$xA|RCG0A7T2pYZmq8_Pw;YA+>p zYI(l6GeS)6Cso6#SRf`)he(^YM#=2YBi+V_6Jt8Ngp5p2Hk8xY4d^NVB5k64{1T#xWj_^VV-47{78Gb7I&`ePZ;-O08)4%1aX#b)6=vkZB1%-VmIn)JyOn&%Q4ngfgw(5`y@OS6U*2yiE9#L zjxZ5AY0zFL;qVk(YmUgQD-Ne@+UZe!5zh0AYWjE5PD$AzS8RS!vN96aj9XevQB5OI za5|bJt67u@P-02?jz-Q-jd0qcbmoZB61`B8_DPCh3`TN*rW{@A5D{FGt(dkXb!_vu znTGJlqNpB1dS~J;vC|^nWa7Muq)8-=e69Jjr!r8DW{&X?`UNGO9zI69j`@A23J-ib z@f%GQ$8xbm&0+j}NvBu&L<~xJIZ&|^(4I04dTY;LDc*-Pp+rqb)R%)tBWgG}41Tv!dTUM}iXr2r{SI1z}Wj4&dd$kb26e*mTA)OlD{^dm~UR@7XQrRP_5 zp_&8~$Xy0igaptrQ+KKkfb%L5BZ5Zj<0@P2_%b3yk(eBP^A6t#oI_Fo|4ivP{8pj=J@{&Xqz|$UnSr^LtHo z9pK+_S%tHb8vdAes}PN9YiAb)SyNXfDi^a$Q>_Wj%f`Drzt!|hrAKv4RUyuvh^rc4 z9?K4N3B)N#<+^4@kje?2q(!;a82r;0ZO|zqyy}2OnS2xhfBK@7AH{U)^hHTfjj7b= zvWZNUC{?r$D0!<`sT57l(-dLjG@e4|y=aTU^qn&HFUJ1U7gb;U2uWcfrTNduzGg6C zh5FkU?QSYDjeG>vDrlZk2D!l5$0)% zsAt+%sZAxFA+jg}GI3RG>KLZdaU*rF6dc4{v*acxZk1qv%$Z2kH*rx+@EB2%6O)Pn zbmxfqDN@y6l7Gm{i7=H^m5N1`!!?gpOyZI-OHeB0>yKJ%*qw>~A9B@H-Z8&h3;;=q zl-+U#q_E8|>pD3lED8f)8f|1zYCn>8ivKU}sK&5NTvd5nF~0)s7}BktXm{+cG(p8QK=P#{(4zDsjrS`A8Le7Ng;qtLbTm`^fJG^Gh>!r~GilU{2||O` z$g1cv+pX;IfoGO%cm5DhGl&yxr&q#y$g=dU## zTN$4g^;nXwl1Q&W%K1*`#A`YiAhzoKF>|X@vz>@o_&1_^O}|%lR*L1Tz$OxlCTOmJ zc!{uAjM~I2AZvl{Ve_aZ4wOc*B$q`CCz5Gv@zD1aF0gpgdfK8(2b`y@x_F#;(xQuJ zcPFj7bcA-&qDv=MCoQ^ktaRF<3kNwTEK15s+`Hz|WYZR1IHNde(WN7SlNMb%f;Vl^ zg(Gj%7F{@AHfhnNlU$P)T{=QFZPA6}N|P2{JRdY=)y14LTVh0 z@W;~0k4alyI%+X((S?%@Qx?TnxonPL+M?=&8&Rkd)yhh5hi^pT6ExK@;Mbe_n z2TUX^n=m6HY1QRJ8B&(T2_DUa?j|CnEW30jLE@V6G$=PnAZgX5o&1v)UD!B3ZOw%} z?9&!q+%-O7+2u{&lNMdva6M_&<^9c5mR;OyJY`XJt&2sNQw#SJx^E|Kb!k8Bv_+Tp zpH5nJVKeBYHJ5f@PFr+g@8h&ZX&n&BSaX%)NsBJ+A)K@*2}ZFnuhfl?NvkgI@S3vf((bBhYcA|)nzrb&9->KWE^gkLwCdtsnn|lJZf%*g>f%O} zNvkew2RXMUzL{tTM$$;1U%$JeK_i2&0-x%$Cy&2+{N1C!pZx975AS~b@#5xpuP*-b z=+n`Xj6a`Ft{ax6m(P%{xolN>4^Mj*hE+q>w{+1xrA5P{xSobgjb*FSYPO!vs~MK1 zv^afPnwd?yD~4rh>6^SPsVK3VrK>4G?$B!CC1`Zvq*M)dJLDHGUUW}&!5tTkA#6~x zzI3M~?#7Pq3S|;+wcXRUV7LG(8-ogyh1;zl+R1FdVO^IcleSxOJ!7av6;?9FYHG}+ zk9pXvYqFWRSuz(RS3nwmDjB%`(o;UhVXqpMl)NmRrXrgy=qZ>=wS=zr*jK@JnP-y< zGAj6K{u#N3A}qIAhPOG*#izp!!+uG#O1#~iob%~Svtd=np$FMp%XZ5cxIIuLD!MRtL~{17*-8(*_SR# z_wLB~h0;k(hQ`NxicW)_wnKLC;;oXyH4mziR{p6}i+4E6WzrcfO&X)3krayb&6ay| zq=&0LK-e%UY)?k}uq;|~Dk79Lpor;+Ok_x>(y^o(B1R9mCzD}DgU#u9;eZNMtE4XLTm=zX&Txg~Tc{x4>CO?u zc5Bz7Hi?B%z~g!q&%rENGO{R<<0-raQ#)IfzWrfCu4SxILuF}nIJNR{3kNA+^ka>! zTexOeNw-T89rH3KZ(`Ul6&9%^fx4oJJCS>!bY&>`S$M&kB{SXiVc2jwe+1!arxMvO zqX`lj4%A5iA+oH~fYYGHvP?Odzg?zUrSFzoi0L3fJ=s!_X`FGylK|UI-z|QE$Rz|N z+RHb)Cq6simsHABfT83^_Ie1@B}IE*G-22-x1X$w!K0W;5CK}X4kjHeykCZtYrOER zo}V3H@?{zu97A5sL`?-9Bf9qVSQu^?Gd5Mlfzp`z6hR5}_w@ZT9WCZqKs!(7=p-(K z6!U;Pz+uq>k{E{sf77>%et+2Y<26jX>W zN#W6=dj@&kiH;d?i#~mPdShKTJ#SVmIRMY_Xn_yMr#IGZ;vVjF{)@S?Adbdx*<^gs z)Y=ICIwwjZn$h1ecD-Z9B1xn5ek zrr!fo#-n1Mev!O75pXCxF>U<-ty*^Ro?ZY0-$_@`SeD^mk^3d~NNs!SMUV@&r;F#X zVdi-zYbK}<%nOZh9-93m`ww%5lj5D7r;P(#T<}TSYR1-e-jp;{V@^U;H6ak0Y}C`z zCLYChN?hW88QvOGO%7VN%wrnxLCd09M<^qm|1z38>LnmaGFc2UaTltX$K8W)fr2O} z4(1s90k_*Qjy#47Fs5X#L*5R3u4DHQH27QQ-C^J|qmhs@bJu|VkqoznG?ZB29kV=H z4AJeIu*Lj-@sHQZ`Y*i$_B1;h*gD-1Q$w$`&}Hg*1c3=V24g4}LJs>Po+Wm&GvGt2cIFn1X?@9|Vz+A4 zF`3G7SQS4>gyS5tS86I_6qX;#4t#5=Y&BgnGT;OWQCb^rAt>j5NVy$YJa48H_bt zFwv0Y#JYme*q-*N!@>tZPE)0I$~pOd(6T=5Vs2T+Ag5CX9i{h-h#9VdUVo{2Lm^Cy zxuG(qK_|0GLPBxJgHzqoFqqr`7h;{e;R66yR4wy@=JA34jLCGNv6eACU9I0?{b~0= zYlA%vjt7LGpHQ-ficY|wt(YVNCDM1y?2uT%^Z>|_9uP$|`s*eK&*A%3XsU-W9Ws;Sw$>r{OJZY;F46-R1yjZLOr5?XI{ zwswPNJ+G)9v|lM@b2>37LwOc;xcIQ~5_yulSH&Dj@++;59M8FO(RKo;zE z&y1^pEIi{+W9tkLMfbXg`)!Dh-vj>Al8f1l_po1+)Y#sIxwE_;p zUlN$^gYRtCOg6s5-+)jOn+`}Pc!D#rH zlZz5*DR4<*Q==jC7`+{|uv(bK5UonCFE2G$Hil=Fn@*f|4>(|=>A4wIbgB1SaK_U`@LvMH2z-#RH=7Ng}&?CHKzinYwQg7 zq0Tr$%8X-8MhOB$QA-P7jWeRtu2`vk(cr1$BZ=#xQN~;`75=4EToWlrQ=<@s2P{mH zPfQC=cA??(^j_FGL@QicY|{N!>kSjwB05?)Lugs*1Itn-9@9;Nfk(@ijRstp4x32D z?6!_Kk)a}4OfT(vnSdS5usNV)h5$Wzh!F0 z8IDOOUT}+lH-f)rzU)FwBabMWWI~xr@{T#PVWs3+|nU=UG)BmaV%N?eyAtuc`- zB`$eYSDreDW(UwQ3H*DS7Y~Nv0b-M!Jy?1K$V|;rVdybhg6iQCv#r1HKJ8G zxd4zz!YvgFF@`Qqm$@s{@5iBFoDH$1R%$#WKf=Okm_kcpOr(^KI z$_^-zuIh~0p%GR#)sOQ(Pad7WeS1N_&c8kS>Ei0*=KS{h=Fz8*zI}6XwR-Xx&h+^g ztM4zKzr4D>y#DEzRdZIa{`lhJ=d)`*@cjJk^Ya%MXV*7B{pX{TM?YWOynS_j#kcdb zHGjYO>+Q|?Tdn-~-R(=aEKk3^dG*t)tMl7eS3j-Z{_^(r;2e*OC5>XxM+J^TKPr>nEj<5&aM}1iJ*JrmkuU=d{`qY`{=QlqIrX(rU`OtH9*?Q(BhpZ}ObW%RtCB+1E zHg(b|*j({<5YQjKJ9uzfI?A-DRi!=yBra}VonQJ-U7f$?qiKuq?|yoD#q|sAemH-7@dUiR`3+zd{{1mKTc51YD!S=4HRH5t`--*56GqSAZDjs3 z(`QvhtMq0*%ZqRN1^YGDX9QVPxmuv0;)*G1;P>MC-4B-+&j7%SN1xu_yt~k)2fNIY zcDX(ygTExG1@urQcoAEqYK=NDY-0YoA%RklYCH;*eW|NbwJyq|ZaGifG9?GN3Mf-6 z80C$*!Ty##%8(58x=|5#z0r_bfx83eaOqIOfuMlHUA}pF{`Iw}o)bqdsp!R2<4VaQu5n6$ zA#_7vwB%9gEK8G<{mmiKVGp1wsH@s;OtfQyG)onQXrs^$&9NYUR2UNfP#P9JJLr|1pZc4U{UW5cd7JI^9^z5kH zP8Dl#Q}qM|ZgpuNOT#>RqQwH9CMORjxvPATx+)q_(~2*-^KhD$^?3o@vH3ohV>zcu$be=se11 zA+$`0QsSA?WOACZ6G+Oz1&|*XLDHld`%{lHm`6i}H~kEC(Muj3^P2Ni(KpGN5p5Ms z=U^%u?p4$&X=ffCb<=5rZ$jWLdvw%2r-?;g%`N&rN8Lu6nA0};tsHe5$#Uy{wvj4_ zXr+hcM3iF#8!1$$3(1m)hsU}_;J{iump>|B$x{Un_1TocDo?VeOO%>6qME?V(OPkQ z;)U7JCqd89OHf{@`onyovDR^Soh)}qd!a24d%>qBk*+N&7iP)BqatUj=-H4pgAt8N zy-~`F_C3WW@sm-NTOnL=rIG$tSJ`oIJXQXznIMHGh|7#WgtMKbU-ayl*IlHFAiAA6 z`vttkh@k)pZti@PIGGxfRp{rTN0?xkWK9VzaJu7qD2r4Hgl(O(GrV>rn#chu99jAd z7iPOAeG8^jwe5Rw_@&9N^_e<;Z1fM5bl8s|wB*rIu_{f_^|Ds~KI%471s#5CJPIg< zATloJ@{EL6WG0~l$XD+6zPmXp!!J{XD>WigVhH$CM1>zwa&*C?quz6>WTpCqz-ddk2D_Q` z0cXW6dUn)pr^?m|&p0=Zu0{1F{t2Rdj_2=+;NxOQvQz~n=wd3CrVJVqbvkFtIHY>a z%dL{dC#n^!S%#+CD?0~1`V`Zq2>kFn@?RSF@Sf#POvms$|;%{scZu zJUZr{>r^>6p<_WLIX!58k@^0oO-sy29J8tsREC&akTShv^=z? zj&d$ZXwkEyZaY;5?y3z_s>IZ@qi#D@D$?*WBfl|YT)~<=EsrE51>=KMR|6`oiP<<= ziRf&U#)C{^XbnvfkGk(v$+%`Z8+s49gS0dwlf~IjJAO!AHwPf~nLe4MP12U?xZ6$@ zj<{U7IuINW45(eZl$=G+j(Xdv^08{c1G1Cxlack}f~7?2$gxJdhg4CiaAqr=Wa{Zr zcb+OBRc%hkQN$jK6L;=(sHG2&y7N>aNd%N?b?}^0Tl!Qg%8^(2tO<-E<3Xg%S*=IK z=O#@mazE?}hk$~kI9C{n>=S&CUHjl%ly6^Nm|_hmsd-%0|MmULn+uADUYve;eR;9^ z_UH4<)zf#Em#Z(S&AGf#_Uz58*RO70{oH;1{FcI&AKu;SuYY^=&9~ou{rIa#pW;hA zdGz$#XTSaax8Ht4UCZB39=*DH@#?ugMY`NjFyd-nUc20X3Q2;pjL)8(=BK3F@h7iN zpMLfD^y%`KQ%^R$JhLySlYC#TLNyM5nRxlr^PAh1QxKLNmZtZ^`>5y%4@*_u@IL)z z;(cE~{=@h0ez;hDarNT)`J2`0D*tP?`sBMWes`K@r$o%xzgm8Fs?3JH6m~BZu?>6C zUnchQ&=5f-PJh0*p>FKw6p%1KdboztUIP_c!!_tHAHX#{Bouj1Ao=g>wTV2af~gJ& zUs;5Q84n1rzf2(fch^5$->$wpfAQ*i^~vwPq=a&_oa>NS6uey}cLBSH8xL>SU%Izb zgSSU|sKR+TOk|Bs6{ppo9wiDloWjA|Gb37E|JmX78W}$I{)fa%9-6p$NOx1_x2t^p;?3&u<-6Cf zuHL;~Wxvk<^l0_v#a~ySUEf?#ynKGM`UJ1qDdB-Sfn2SEWHcngQ6UOzZq^hIp+|qe z`ttkFSD#&6-Y(Woa9xMUYg8rNY39XybR`}B_4)IcudXguZ=c^>{AG3Z?soM*Q}JCm z=g1g#LO`Y*L3)jTA?StD!-k(ymB(gnz;3l_|+_;doZYh{3OxJVn&oP%M9 zx#gvfdkzZ*`oMnW2RBx@pyiQjA2BcnHG1ip^UQ*V+2xkmX`Di^V8HEX7BsAj4iJI5 zrwYGt!GMeJU$8NpDYu+SU0jA8F1kX(&*2qXHlq$f!+LqZTW2GIhE1@_{ zH19LO8cSUc@wQl#@1d@TA_&FZ*0{E1p)dEDkfRe`fF*34aUqEIaJYwZ0Zt4%hvXtL zOae!6^1^Z;N6}l*2dEUX_9xfxuIRV&_TAN=5iyszs(zi*?`HK^n({Qx_rGi-hI18` zbK!doK;XE)buZuQ1LYf`uy6~OD>|;Q z1%u;26Q_Un^8Cl;x-aEL;R`L-bX;TmLhAMx@DNQvA9zS%xu)Y9!-4@{4>4(LSbX#D z_AQRKHz%DYeX^pSWsR-z?9KUeHC%E^3}LwhD?>v&gZ)`9tj5X#koRCZJ!-I!SF{bH zGt_TCSJSCn55E0;^_$D{tDk7#^cgmg+n~%K^~_$bWf8d#H)y%KgTeL!_hF%#TeET#m=ZEF75)#hBJF(1A-CKt{ahsTUt&1Mu8u)9*pJF4o(sGa(Mp#-#SQzzi zpF`=vlW8w3ssn`u4Oc=CS>8=&uK+~*Xr|vndEgclH5)RjPh^58S(4w=NCvN1SSalzaOe00YDS}U*q_|>9 zU^Vz-xtw~{4*263zyzosv?lgJIBDOr-u7@D2@l;6?X@?>Y!5KHXnbO*&8h&jato;K z!`9wDe4ofe5kNi4y?>i!T^{CYppGfT`r7KL%2*j>%s#AtDA0Iz{rt}tw<|IoZ?CUb zFUgTyDOJx$pnddNw$)Org+e5AHCE$RI!$mjfz=W^?;f=H{kS>uUJr61J?NYJ7}EV1 z(v|fdHLpL0bZu1J7*zX0x}C^h=ZDH$<8{$&i6IY@t{+CI1dgUqsC*bc!iSt0*XwNx zOu7KgSO5O?Z@>BXuhXn^ibCLrFk(e^O+ zrqr~-6J1;PxW@klJCL+Z&?-ZU`{MHAXN~{cW;}g% ziBF0Iz!$%)C>1R~c}$tE81>te)mPV~Y$%3Eq z!<0C=^Gl6!*I46D1q1i;Qe%fS)()Z1^8LKj=!=cj7gZ5(A177jZ2(iNvZ!j{US4Xn zl*Vc)sw}vdml_GsSP7u&gL`?YkphjC0vaWLFE2F=t+5P^&T9AbQp2BG%b(;HyO)z1 zj?`L?q;iORd8y$@t>s9~J#i$Z#SV1ZT8^Z$ihDV!;Yh9JNGfHxkC!UPG&rf{NU9>Z zmzNrj)LM?Dk;_vr?Q*bBR^OG6|KmRv$G{|>g9BPdq!NKak}pfhQnqTapk*>j_zxD` zbASItM@iAe4pSJF`5N4}<*%xD2=03i>fBi?GK}w|D)y;uqjTr$HH`10Dt6@SRjJcJ zKp$1HV_)w_Rg8vPjQg7w+jnISA5}5+Gou&c{amk#eFo;RP!&rN`tQ#H^I=4pAD|<= z&k)EC%n(qa(124LYn-Z}bkNxLW#sj3>6mo7T+=sN+QyovsuLYvyDuJe&})r>y0HeT zsy~OB>g9f2)hq=-w!Rt}7=SDmWeJgdHy_k45r<(-I`QXE>;8=IT1e$InVxv#YLL2vFD zWvPW7)0(YqKA0WUy6=|W_cS}__*UO@{b^Es-iGrrpvkn$Q77vGMfRnK`GIW1ShmN{ zFK!u`>x)|Z(QI|LJXcFiatB8cGmGt}OwO8Xs5_Cf*1!G9_0^BBetLIv{=?-(!VXNf z7_;K-4i=@04HxoBaaOHfT_wEUFwAUi6Qa~gdw|NmT)_jn@E3M~X12B|Q5%yIwXY37 zr10d)|MK|sao_TX4nVCNvc0G@-%ioY);2eZA@SkS_vC^dObvGCX12C@N$TevzxM}8 z4G#b)*{@6F+CUVOT%uY&Z?#YdsE|w8c-_Xt>-KSp2QA$Inj4T>(`@&gDTAv&K7I8w z^Jzc3IaeRf|6H8tsP;nPO<6r)WAp&m^?HJzKB&!f(dWG#NKM&n8| zBa-XUywbo7-#hT3P&bc&EbREvTHUG#Ztq5cb=SUs#nE(8J6^Q5<3$(EEi6XELhZEB zdNeImEHA!ClX{!kxtg_|tLdhY#aFb9*pA7p?U+pQn)rg2UuA}0)pp{g>l+?l(Ug2- zcI0JkM_#&dKk*eU&DxolwQZ2SCBNM0LA9NudDQn>D$OmG+VPe9N@@}$fLg3@|eOHzqK6_ zdCd3PQIeURC5a9mssl%TujN;T0l^y+f)c0C`W#>QEcK)NA;dCTE zX=grWh2>Xv=;Kk(Yx$M!zgOFNk4Js43e{DxO#@|~kmVMOs)^@VuQQ>R(l^wuX z+X0MmeKG;BtbS$ZG}g|&en0eU`IQ~#Sle-qM}@EDS9a=S?Q+ZRFb z@`&dx?U2ZW3+U({rpMZm&)Gjt&$0IJKT4l`e{$jd=o?3tzl$UKr2<9)K37(6 zw*!&m@;BkVR&TGY-fpM+#^1ZR&r@l~oMx5P+edRw!G$UN_cK3Y@k@GvWYFTTbNVCsA=R7Hd{Y*SGfYZ5l`^wqDQi2Hl6#!mV;6*VdmQb| z?yFcHq~J|y0uM?`CdD#C#$V(G8)!{o;yVkhrriP=*jGeo_aK*=a}!cJh`?!c{Bm# znD4bbxwbsn4njF9e68+UTb^vkdK~q=)<&>{I%+$pOm94<3-RzG0d9USHwraa}J)`gEy_R3u2_ChZ;Bi0iwfxGK;?!=4 z$GyDQR&Qsmco@+;dvx^|;H?&rOhU$s`h8jbZhqJCwEe~@=?vZ+SXKaTlc z%dc9iUoD%0aftqGTRCU8mve14NI9yN15<~>_}WxF}owwv=&&ujVB z#^wUq_Q^+mujN-8YY*Daz{h;AZ4I1lEWfh7fsguL%da*zR%JW$hIy)C?&6&)pGw=A zH``dwHEPWZHcnZ>rv4^R=nGsb>KW3NZ>@#VITuU0T?ugMPO4jxmZ_3G-~ z>m*FDC5O2!Ijlz|hkG=MZY#whkT484Ut5N2i|A%<;vo>i`zFNZl+G zg3=bvN*BpWR%X|M}u(IaXT1Y-guP}zrDI$J-NQQy140Dt(<1dQN*epw!*ft6}B!)IYDrp zsM?&iO|sgf2vvZhwjQ@}NV)aPx(ddL_q&{vlg>>2!>Tw#`%1V0EBGJc+B)GT37Xu)W{@4+VMj$hr;zA=T?dCP5|x5oB)a}`VR6|Kj@ zc5rKK2RB!X6kpMr|F$<&{*7CDm*BaY(Ep#Z%K*k#6whu*P`>DB#r1&1K zg)|6hJOsA%{-N-ZF+Lck@ZT#a{`2I~6&C&5 zN1y)jZ;zh8e0BNa=HiOKWGDGaaZ;XCC-q5l(w=Ni$R;BLmkcv<>ZJce+DgUOZg0-7-d^?} z;9*hX6Vi}E`kLXCJmFE6m3qVLi?=TyeM&Y?_o}SjG>@zLzxsTO(=V?tFIM0F%&^O+ z?=CM_Us4}?d9iN~dcQWavj^T+5guKiQH@coi)PbqDC6by`bJ%Bh{6`@3}0B;Za0M= zwA+-&Cc?PRqw4E0bqjv;`0KjQJw3mzWs4r#U&_zZ&nYzc9Ud^6itb%d2vG zOC(*TgKh^w))cmdx6!)eR(aF3+dC?EPL9v8d-t>3n^)8Tt-ibXc^3fDL+VCH7&<~w ze2M9&G(xjVi0kcD-Tx7`R!x z=fYjP!~~Z2$Jk=Zx~cOmtngo^VTy$lRk)jq9SRf2pc&yLe$7RYDbE@Pd9_ttLXhNS z)!YGmX!ooqi$A$@D*<#Tw!JQB?X|rjyr&Ol-vd%kY&(NN58GC1@S=SefNle!)kQAK z%5rzz+|U@ePO`H#2)LmU*19b6a+6hjw4Q*>&V7R>WGmQgH`rY}9SJ$gge)lDr;7nMRcnIaM zzS({L$@xzgt0$MQUjG2Y`pc`^m#ZJIS>U{rudDwp``_Kyy>w9ubN|Kf$TN52N>!`Y z)dBC3#%z6>q4SG;L-Hd~DzciKKOSUxGaPJS=wBy`lkTM~?qs|UJ-+ImL-ncv+X>0>k}Bny_UzB{wb(Hz{is*6H@Q@OAfw?mOs0`xmf)xLt*<#>{-2| zY2~~(uV5<`|0;_{?34>S13YJNriRX)n{`fjLB9Ye&T?%fXV_j&(??W*te!dy>;RtU z&cZ*qdQPKrlytb$7dj>~$m23=zh8a%{pSp^y}TW(gFXGSz%=*J?XA_;eSNm!#a@*c zNe{0YM5r3tygr8jt}a$@U0?01ceh<{?Ws4rx9)v4zv%SfjV{G87=$1<*`FSDawi=oJG?VPU7)iF1c!(Ep9;{ zJR4p$l3>mFY$$Z7cMWo{DD{E{XhM^My_7v_LD2};4C3@s7Dli++iWDmik44v%NM6b z#{2AU*;w8{c_`F$Q+>bbOU`cen!wjr`|_285aws>E;H? z$NF2713%o~APBSamd;EU7niGNZ{FSXl)hel{`6$kzJATqOK|)T&lpU7bJ6AcXI!^u z0v2k#Q=l556wDlSsLE=yrUSt`FLQ@{!)6A#*aLGt0n9+y6hhFB0)k1=pWVEB`||SQ z?OWzn?`6O{K;Tt7&m0h1#3Tca85x5ql9|S-mHyfCe{>z#6THS4G^gG^WuZPZbh~ktUM+3bbxn7CuO;oUA*I$&~8RM>2Gb~@zf@% zJJXbdP!`zROOOTQ8xZx8XEMPzdD~_c25!NcJe|P!-A7ZG(&6=nE+=h;E3E}gs6pH|y))Nk)6#3#{cnq8 z%0=q7{Y1m$FK*txyZW=6a<2gtr&*y%6lYB}J`Ri!`f17rzEM&}i_rHX%RX-!nR&Ig zutUYWk9N+aor7nE(~H;UTux=$d#phKiFW?m`RkSBKPPhM*a7&+2ZVNXiqh0p4II7M zkOS7h8vQ|XL>42@9U zAY#r?B-zz>5a5dy<$N$2b(~vK&i9+k^Q)gI{re0J-|ZO8z@1u9xHEWxH5@bKJ*8JL zJCqz)a)*-Z;#4oNx|qcm4p+4ST#x`d9zKl{MISecQ^B0_GYBls+i#=Dzh6Ch_xASs zwR4?cOnL6dxUq{uvM6@&W#VI#z^N*n3>~^V+!@p@YiOw%Y699$x_2LxUX4fu(0Xq|fUlr}T+>qhRH*l$4oR+&* zX?unTj>hga@~GwG@J$q}>Nu z$47pDetFsRz*X1rwPSrvxx@OnF7AqMeMD{0ONwf1i;g5XLUR1k(hJF*lPP9nISfb9 z>TN*Z@_k|1<>IF;z98LxvB6u+6W|BB48R&V-q)|LUcElQ9P20fS%W_V0gi3U)bV!X zz57D2`mC)mdXaKy7KlHOBqeq)?M@MhU}lR}tH+buu5d=liUJ$+qLZBnQtcNl2nT`8 zC@VhI5Vix<0@gUXXB=`eIs$>bv(&7%J658Z zbcR!0s1oUc6F(w17*cJJ+(InigQF+6?ZO5H}HieD~Jme4YB zJ$5>U*F907duuXqd}{ny_x{7=u@N&AId5>QI^SADFa>$MxwrM_d8xQCh*KqMLnDi>#c77e-X@r>fd|Eh}Qs*3@vd zzvj3);{9F&3-ZntZ-0cGsWSq1uWiXq3d^QU*jcuuR;%4P(k$3%-7=6zQcxX!c1SC^ zq#x(+96y_6Ls6?m9XY$rA8fT)60gpxDpL?2T_>*^2lFYKC+Fr&Vrn0D3<9fX0vX_$ z(T4c#m{de(n6Ow9;9pMW3-VTK+urB9OH5v?R3dio-3mq_QuomAK98pmiEHleOgwYq z@y>?9X>WOV7&FKE)Qhp({-l+?h|%^Q#yvq2b)xFtktXj5rMVO9-}ps{-x8%Kc0fF2 zQWpmy3SpuXlQ^XGZ=-Rm`&74+9>=Dv25(-ev6TJrx|}d$1K!W;0NA7zoy>JFOWgdpN|HL*+{L7D=aFL?6%a+X#K&DlYOaivP!=40k5tg7^7gU z8~1y1kl~$^7qeJitH`q3&zI+Eb|!#g543~R0eT_fZ&Jxo z)#p*Sw!OJM;9S15frZ`~oReI0S4vEK!JUVB>@lAr;Z9{3uwbluso1o;>_{}n^BOh0 z>ptHxCK@d6y37JzGjY&;vTu(_++AVks6wzgZ-D06b=y9k@Y~{*{zFV^_;G=y;jj9y z-AFNeUY_%y$#~rf4$67xz&G&hUarUq4_z|8;orah?Kl7a^^_UI`L+ykk|}D9J9*sj zT=&O2+@cGxZsgG=K7AP??a}1p`@>k+yaTc#~K*?cwMY z-#so4wY=+L7t8b5BGnYLy8AT`Z2u_Nyo315;uy=#1n-S;l++~!E%(Z3=wEm3hac9O z5K?Rb!pKX23rlecdAKrihe^cg`%b$M0TUdAe(y4P0-TM32JL zJ8?PlVXjct5VsoMHVBx-*(n`!TJqi?KW6maK|;*Ex4V*o89RWMJ_g+Va+k-pf&n~s zkCSNRo4hv%0?uAS-$366<7Rybn)ug2e=1xYATcC>?ITHt?-I|;+B?U^b4R&!8|4Qm znGO#&!_eq|!BheHnRcTVTpSDbdLxT(V5S`v+GIM72<$c*^&>k>>Cwf})g-P?*dTi> zM@VsV0LLa&lflMYWh zN~ws4P=si9#?V3#c8%se1jjU~umip01;u*8rrc5NZ5{)$o~3yV1UuYEcQAl0t`*iT z8KuZiUKPyH;@P14+t{uKBK9adm9{X}pj`Sy7lz!BkG*ENyo$EgZBNZy8cCE$z?>}o zjZ>_qc1ierH%OF|Nupcc7bVij#HG}|YcFsQI}jjVUs1=Tq+{@+LD6tb$v$pf)NVS~ z6{9!JGVHb-rMDnM5U9aK`9mryKGux6OBvIT$c^F;2u(CCBd-*ONu?m4Q@J2z4|vk} z!{_iSWoWb+3>IGifA}0}w?r-Z!{^9y2TAzD=SXyiQ}c(?%i3oN#cFp#b=k-&;Pvo;pU^-Qo0gjl8uDo>#yhFOi}Nq|?E1wo zD<&nEpFF1EP^9+uWcAfGsVaW#>)YLk+BmihN^(N5YzG-89-WTAjW~1Jo4aS@eu=2+ zaP7LN)ToemPzcmAM0U%)2Ng$C9uGL{vzOP@G44C8#Ox_CehJ?K6_k=Tm&{J=wZzj* z6_*^^Xn~FAHIy1q=te*nr+ta+kg%S{^AaK_3&+83!2G+k4*cAg@1+{SLDG!`Sa2=0Ax2isODz2rTjNfo*t@;2#J| z4D$N}+3+AkKadR%g75>`@CPR5q%3}5T;c;0bW+1VtQ!uB(mxEM3rf-FHoU8rt9sO$ z95`pOir3yk#z-Elc$rW=96Q72Wc6M7_&@$*Y|T5xm9eCoTs5Q0n`KscOL8Y!viuGY z0jBY0gHEl7vZ~H1TA3GA5@P0)!il0i>E~i={eA~En-nb7k2;f{e+)TFviFv4c%i+6 zTLu3{N#-Y+rI^IN2SM;uPP*FH!A_d>~zYk)&gWUTdw)?sk)@Pq}wrF^QbMPkAd%1LO_rv zC3N1P^A1_ioVdq~L88u_0wQhIbCMV|O$q6u#j0$WgdX~UkV{E|0MTB+$Omakp!6UD z>eQ?Pc2~eoh?HVlT8z^5kUjxBH}3oga(gJNfo?XwkW4K+l)gqRvR>29j8B1oBz~;v zyh0Iv6}WYR`v3WZP?*ZHEiDr1khpd&73cs}5=s|@$S9%T8fPP{4n9&sMD85951_mr z5?|HlsHCe2Ew|IzCH!VX#I>Nxla6A1FIV5rg5n=~it;al{5mgiYiV0S8VfxWg9ct4 zv?tc$*X^sT6)hZSe?$)ls!OXk*GxU`PDt)b*8{=eKDb3mu2QZje%e5gyp7l{a3O3> zM=Sa>IfPU02EBtIQMLZ0-<&>Ia@$;OSt(ZR+woe58!!L_EJ4RM`lymM0CG@RSKtzo z&yC=-7E(bW|L5|^(P=|K4PyI{#7k2EGMzqUVcHn&NC49D&0vb@!gL(GmcD4FiKG zWkVspWMmJ38GHe5IHGA8MSIhXc0Le48Wm6JJSe6Kf^aZjE{QnRd&O+Y@F1y|9YLvW zLlOrYAYIKh?Hp4kAR*k1NM#r|cQdru)cAp5(ODMA8TxuF5}hE_9FwK^F_x zLxJ0)MTh@qzNbkCi>p5YJfx)M5}2$*!2`)_hUvpCg+Dq00t5a4vnY8f9&)!CdfdXM zxOquG=wX6nNp_=~90@JR8l^R9d9u0MhS!n_hYlg0%EO8agQn;%2m9LuJT+)+v3soc zPmjjvwo%GV4x6W8hR{we9VDZ7@`>2W&NIFYrL-`|N^)W!S@)D7NI53Nd&G6Oi9{h- z7Kv%VG-iwJ&#gVhGbe5uLZ(htAKt@i28(t-t*Qz>3*;sH4N-oqd5CSGk z-Rtxd*SGsVyRg4f8fvMUh16mfNi>C=X7es&-J_Op+XAL&j^6!vU2Aw8mVA6%&`c`vmXqmT)2wA9>QBfm>t$D9coL zPbzX-7koxqch0BX-P6E}Ew)H0N=f+d34}ol###U#tRUM;dNpUJLn+W?fC5Ufzh|zT z>`@ph>?&XwK?93Jv@9Cfq1_@QqzaH`?Js$P066yqQ3%nv300U#19T)camb!3RJ9F=9}-IV0gY*4^nY$ucSqA z1e7X~rg~VYd#!LzdfwFD;d4lTloPB%`cpb8hxXu=WXdArv4~yfJsK_Q3zjw7G4vW7 zXAqZ*)D8!f&^&co|HwRbn$*}lb+s~M^K_T7I8;X;bIK-aEgl+FUHKPOpaajxy~Ae; zS$4Q;(D)HtA#M#K^$@l~-g40T2R8( z?Li1Q9 zx>JY5NPyEhQ-SV>j@RLPfYmV_1)+cuuJxUB6k&oyp?)?*zQJui1FeO&;-~mX*;0YlDqys8qw=qHidFaFhLYM+N6n{Jk zm`_fuy7sy3FJY-zTwx#Em@MM--}rOeH6FBs2`6kU(FM z8MMTn6>b4(kEK{TIyGfSl z!DU`piZ;vdKU59GeEc8FJowL0Rzf(!#C<4C4!Q_U4rZ%xje!W@swBE7{IQUW5Uj$N zgbeF8owTYBe^2a5zurd@0@NV>UJ7E8c&w*nDym;6a5RICq7<1JfK2 zs`S98fR%^`g?bQ%4W}X=yoVKuvBM*@r$4`Fmvn2fYGP@p6u2anMhQ8c`a&SI0~kGy zzfF@y3I`Qd7kZrH;-ElF;t;kOf2+3h-y`gwxD{C0_FAA!K_PV@yC7TmbES5KR;Co? zSZt8W9!ZhF5EJ6=pjgg0pQV#MNfEV4$&<#glK**&t;$V$X|YvPNiQw7YAflb#a17D zdTFs$u}Cj1wki?nrNvf_Af2?>Ce2TJX|eTKOfN0A+WG0F#p&+MgSMHh^re?EPIqUX zO|GT%GRB{M=85_ZDAp+aYA~=6&H`dDA{|AZ4P5C1AAlDLkzB~-FIm3$FLsyz9BIc% zA*XO{CMw2opnd9&A1tNhwfyIo679^5f6iPHmM}tnY|ItdcFC>&@0lwYbNk_yGhw}4 ziL}=+R;+Vmy`l-9k*L@0FpMNQ2H3__`SdkWn`}>iJ|k$a&3#J2e-mBIDZWN1NMiCN z*hi`CP2pln{gtEDgj(#vrWdR4leaEyQaydng#2l8oqyUG6OK-+MQoD}>R&2=QnmMA ze~hMT@4x;KP1W9i{Slg~z5jZnF;#m%`}q7H%LnVhnLgx$^~g*Q?G-NB1%w`cD~urE^Mv8=CSpGUXp_gNc2MP-m2qW8bhSyT$^kw#D+kCM7s;<$ z4?!6wi3*;wDy*k{C`alwB2Y4Vh^rtV^$6rg^az|Z*mkL3L}Y1YRTV^Y;@X|Kdm=6` ziC|WT6dh0&38H0C)L$+OYxJsM(aBv#m2E8l#Qzl|RyhOUimKrLIJ51OL%3Q3e5b6%qOcK_af^VeMc=RRSJIbQ113z~zNtU*yEXf5OhJ zS_M}`@GXL75pbU#ao-Ym7Q{cXn8YO7brxSCco|C)m&_n_FcdbUY;#ZrRjysT zVoht|79st;Qfwfr6#g39KK@p0p;WKJr6#;x4hH~NxDh8U z{^4e_BcUTkB!z^v?Y>pQ{_U-VAWy7pT&6}bTT!F-Qx%tT6{iMCz{`O%{|H1dq!O;XwS{$$~aym3!`gE%&Oa(jfOl zjAyE*L;Fhoo%klz@oCpTvGvlX%|N9~?#O>Zn-N!MMR`Q|IBXSS?nU^F!+MoMORHw} zgbGzNxotR4C@G@aX`nuP#HyTgwAbyH-TnmK+O42=T4tywK$i6l@t8H)DJ6qEYml{!f6$6}PY9Xjm)arH)=+d$q^s$fuAL|&{ ztYINVMVvFj&rz%uH}1sAfbJp|9v{V&iu*Idj7s&I=v}I}1T0HAC?aYO*DVwEaR(DD za8Rma(RPBZ2fa-dzaAn5f7>?Btp=d7eV6Xtoa;4kPONQ@%M^*CHpQsGIK?F~gd|pi z;%ptAlp|xS(|sH!+h2n$30TW`VBg{fJVHwG;MankB7znV>|oqq!nFuIcn?<+VSeBd z{jpAn%$$NNjLtu~*#&0`lMXpdM9~FY&d2gdES`edaJ1zRw2Yh`Na-N1o#VQeM1=OQ zI+zkHM=VHrvFfw7n^j3k4wuCrPQAze<(;s}OO=j0Vbws=aVM_6=RZU69ov>;^ z>9`YCO(z|9!fMB-<4#zWm~`9;tLl-CJMsU+iR~agRr*sqY?4-`-{oYJx+)!a;?pO# zt-25I9~`oHpw=U)BQl-ffm#pW9vq=~p#CGNBTPCxcn>+VV5q~&5S|4)b>HoyNnvAo zrP7qewIjG3?KOB|U#C#^r57@d*#VG>%KdNX`ZkHNtW)jw7rOqxs|Swsf%Me_N6J9@ z>VYFoAbs_~ks6S`df-S0NLM{@kVFd(sq`d^Y|?C{Q)z0GU@N`$z|py%zE+VVGd+Fv zAl;wI4l;J7H(8YK&t$0N4m4~#8iI@XNI8H9nmWK0(%RyIrjB$DNJ0k|0F55$9FXq^ z58lHCJA`N85j@6`25%pj_RnbWG867+d+TAeIOxUy=G6RqJ#diH>wmV_{$>vx`RV^h z68mrVz>$+aef8j9bngGnIrtZy`+u_s|DtpMZ}#9{WQ+gJ9{h{W{lD3RPoMk$xL56O z_8{G#$qrIxrL!{`VIb*TFS5xn^*^`8|K2`;TK=gyu=T+sPEO>gLx2mO)LMBpMAEpZ zKKj*D{2a75;#@QN`a`}2XT8<70P*r5`MG`_}V8%5dR5ox;3=Okeq}3|nb^yW*k?2rXr9ee3 zNo5?Z$ZDckMcSgDZDR6ZLML~mR-fLz5q_s`+p>+k2~{VgV_y_2YaPGDz;FOjn4SJfc36ycQ&`o7e=O!YT5% z`NI5Mz(W6;D+>Zg|}BV3Fb?B`(0=@xp`maN`PC(&cEU z%TrSLM$_eJr_WQ;Cg)c=vTlUaJUuQF`1#Xiv(x7(37V3I(YDKRBCeRF%t?fjg)%va zWY{17$KiW+ECl=u1?G^{{bPO<0pdObiU=T-+>KACVzVJpNM8a91Ue*hP=XF28z2g~ zS3+ukJfKLp(1?%_c_7;f9=wNK9%yML6qdt-_i+0GWgqe2J){yrwi-Nm52N9R zI9oSFs){nVV6%Ae9$>x5U5`4Ec<>$wqNw8O2C9R4hlCDS~gUp&%fGkj6a=SXVLG@KT^6vm@ zqi(1xc%i2kxTPnCJrU12{?`7-9W6z`K5%lRv_Y~K4-iH40snv!#WIzp2W&>tdZHmm zqq7gFHp(I5lSs!0!YxU+u4RuNNJ=BV3hv#qTbu6f+NE~Z*te{b<1RS<*8a!sI)+|| z>ZEDxmrY`}&+k{NRUzs>xFBnn3;3xR(!|TGUR6M5J&ztSr1 zl76MTSezJM{N9>Kgx0ZJpRON=DEWu1yFTfM+)}l}CL}=&+MgwDLrOt+7i8Q;v0Eg` z@<T$EC28dBCiU;HATf(6|C&{%eCn?ykB@aPC%x%e8Qb1=v88I4 z!*q3@Tt6tSV-2YgVF)QEJ2}>fiW8=P!JuJguFa#P6Fs@$-myUs!L60-jAI1&_} zqewufPM){_RFQCeE;|}MnJOcNw6)0;lVTKYj#isZR~dpG$|{s4q$RF~3fVHk)IJX| zMmNoG+6|;ANS#XHVx6RvxHh?AJ|%H&jT&SjaYGgoRBp!uLjzezFba5JXdnxT8?unN z*=8Z}?%2DMbL|dDu-~zlvyaG~h-{LTgoJGE-q9VQnXctO8XGplgB^^l=tyIY*i{rr z_i}-&RV;DTu=nzGaaVbwRy9&MV>>(e%I-%$JuoiSP?;OQCDoW%rFwFcozW5J+TBCC zp>9B;`B&LBwTMRpr3Np4Vd95B`NIeX6;_()sH@EZ2!k+rF(-*`Rb?E>pVkl{&=6&d z--C+x2)%XC85`Luf@3QsnG6k_-5@6Id!ef0>4AjcFeBZOz#ghV(h&nY(FHzO$WD)H z!n#6@ZiJLWTYwRXrGQnD^rFfIMu0oYFW|qzY8DbUrL3}9mdQ;{sZhbHOCAIn=lWMo z7CQv?AF_vfqJkiTDA5uj^I;Yur)V`;*6x^QT(PZ;0!m1Kj*r-Lcu(|Ayoe}EPuRuC ziwfhQnhclz>n5Y1JGz#1HoZQz zh@AVdM}(|!QHk2}2>nbRXccm)i+t(GFpA9P!pcqEY9w(_RJf7{I@LnAIbzbXHmX)Z zlg6&DqBJcM{-?_zBvRdaN~&#NHq@DK0e z;|iv#Q5!8qHsIn_8@kEk@Y+5V8kAj{O&VzDB2+{MEaNtwJv z2~9^sm^AG!AB9ZH=Gf#k`IL~ck;NW}HpcKkX~Q50{Vr)(P)`X7hvBNi)Wh*2Tv$*} zk#HE7-61$occohLqK2jlHxz^dra|m62O}sZ8J+u-6thWU^63#w+KV>nLLB>)Y&vH@ zod0cY27USrZx5`HWI6JmDl=Fy;vei5A=prr1Pexll_!0V${Zfpi||9ircX?NEnXL8 zZs0^io_I?pK#cuo~w@n>{FJxO+JJ~nPG34+v;H(yoYn$s7wOaP>-4^-8YjsDh7vv)Eib^PL z9BGm0e`;ZwBu5>6Z8zc2&EUMp0V{s!qn3r#*tkt+oo8so$y1qh?WmTzb})2BYnhhR zilR^tZ5~H|7-_Y|Ulq5*5|ulgj+qrHqsz|w_yhD=gDOc5Y&)^1DRR??KFK0W&E_b{ytn&XK znCi5TXVO@uK1S>XW~%*WJ*3h;&wn|L)&-U%6_2MCtn zT&H8N-XR@Z_37PFq=M+v%DG%X9koNE0Je)sfREA>c^RvTn1WB({bF_!6EeG08)orbesq^ALez!3#gFEcYe20?M|z zqUa|)Ht-t4r-jaWVHg1i;2p!Vk-lPKVZr}}>_eyn3^yH|*Itf%=pRLXqTkL zni>smf)GGBIkBeE(2sQs;Piv{!4-w4Jy0wVA*D#Cftub}HSmOb0?JfN_HaYi!zm^5 z)L@xZb*Raw^jh1u*=oL}vCY6$Voiz#i=`@2mZZX-E-0;vGKFZV*rc)qHz)<%L*N<^ zY*hu<5JQcMxx$N!a(ciRs2Gv9<$-?S#bgO(wbIhmYIOUv!KYZ0DgLOCeu>*ila+s5q82oPG=1J+g5P$G5VyCI% z96@++Y{RPy8iq$KyCjt+O~=A;8KX<)=DoAMk4X-FRYH0=en9-eFD?eY{H8&L%!{w^^xC8gB$s^o>Z3>D}; z+6{4?7)BvmpHh$usr%`bC{Mzq)`Pc+_NSDYpM4}^0pi>f)K3(Fullk5DODjaXqc`D zpMZxH7r_vmga8A16bT(yl~TWQ*n_0)oO1jH-%Y9dVOf6G_~S@No%pJVI6}2?Fd`8N zA%{Pue&LC06s}bO`Jj`iywF>r{mEBTt1L49&u;u7h;6nH6k;?yWmm*Zrs~RPo|&oE zF~%58#$e+lfN|mqG4CS7Q-t~oiiT{HqL>mEkE?rfS5j;QfOtns2}1y#A^D$lb|(e} zB<~5K)~D!+z-`Hsl7^eI&vTnZA@8>SqnwOBtQ zj3sI0Q|e37k72hRQZ!$z{1nkz_`9Ds;`sR#rX>UnerHNE62>&7c*^f!1*iH^4E&!A zw=g$94z>z`N%jN&8J4H*!H$?p$VEIj)M2~1Bi`B_!R#1VJUG-*3L9b{P5YdK-M%6- z5&))*qDl-%!oZ}8qC#zn6oFZY9}_!Ep7|*wv;J(nY^_DxQ$}1COYTXU)@8~#Dvysr zKqZyYlKjWhFvDq$ zkd&@8M`4%Z@28HtbkyvW+LHZtg^HHk>`%-wervDRZM(HCr9dB)pL&&28V@Sft$Ulc z;*(3$Uz+~n?Ccy-d|<{}8ovyy@&(Z9%@)>V@)F+px*wemjgy}*uJxsfqa)GHMp^7DeLezbaSobtzp9Om59eaUsmGv)4_9Og33d}!vx ztIDBaIn3GWdDEp4`;_`!a+q7`wRCaP3ZSwjVCOk(>&vzyJMw6wH97^^TTyV-w;H)*pUVF&tWH^(jXA0XKn|BVN1AQ#4eu?bn{96NwRfu6ta%49@NC=|J zS01tsFSD69l+jU(8|PT-YuU`Xs_JRdcRN`91KG??3L0p~>iNudLpJm4a|X)Ou`jzY zC!0C4rI7}%E6;Wf%Vu6;GSdBR8%zP2_R%XA=YA$QgQ*hz!O4mnO%~Sn#M3YV{ zqt0YCzbz9?9edwbrn9W(b`Jt+*U@NYQfOB5$$0_Pt+++$Ix(v`G}xa)#w92X`)4&z z&gn-LouZVCt+JY*9rvNjBkw2?+N|cGE4?Xt_Hm`4dsg#_m0J2Pc$3nrcviFjX${@0 zIZY{?BdhtGvxW+vYNoV%>13V|s-}6>b1T|wPUf{u)l}|!f7R~&PUcX5HFYnvFnsEI zC-bcSYKmHL+_Z6ylX=e-HJ$s$lkFbnWNzL=LvBrmGE-+KvvV~qP0t$2rt6)|@g=;8 zhwWlRYB-tARefmkh)b+e1t)XPw!Y-i zvzRqM1yZSqI9Bsa7PHUrAo8jh!KSh-=4LFI8cn#y`i5pP(|H~BKDwVho{+_S=b)ah zeZ7i>_se1)H_bqAn~Y)CT4piFx*2Kj@OtdIHjCM5k&&82MVRinWie+zZ=~-GxlOEC z7W4koM(TCOQ?)XC7IVg#MmkVEgJOJ{+1#?Ukz5b@D|N1AHdpw?KmlVXD4q6aHa}gX zr|FBchj_%nams3tLgCLZ`f09CbQ8^LqpHBXD8e; znbnUq)TPEOrYe@n?0P^;`L=FlnX+dxA3owu1v{Q%KfKInz8mdBW#`{xb+2VKFL(7L zC+}#c+Mm%}a*#iHTM}6Iu#D#V`vR!qjszAzJEM8Rmq8RdIf{i1%V;j_9ZdP!-(`Pv z&S=ivQ%8Ldo?vEOM)RoimyR&CdXT|f_p*`JM-28VcRGXln@vVq)MLM@5zAoS5^N-|%5F-} z&eJ?6kv>D9# z&IZxj^^cXqZW+w$CI-^$im}S0Z}I!<1kkZX7Nugg4CcOX{HT;FUO9a41JAz2mu{Yk zP=;^&z%LH+A@|YO70s9roLYEOIwf zWX4-Qsy6CtMZ1=IcTH`??Q>{VvZ2gtez8t4nfKgPo+Z5E&z*wk+`%a2*pXL!CdavOB0;G?{}m7E?N5UrB`9Tj zz2aFa`q7F4(aM&3ulSs2K2)X7J!Nj;SG?$cZyFnQQaSe2!VSB%)VK6jrP?kF|KYxd zhEJcV@aYy_)P?%n zn^~{S3H)RMABt*of#tju&xh9arM{7m*vpmiyxv$p((aF8B?iUw=V$#XZimVx8`#HOt5XZ;-5lqE?y}?!*->3bsuc=)kD3dixivy61Z<(;Yj(^%f(jFHwjyPEEsWBJ%~ zM!J-xkZSj|Sl)7hk-}<5samv;-Y$i&)-pubytKS*0Ak z6~phH)RDpOfYN+x4ENg-OeJEjDXK9sSOY<{wR?n;p-~K z6&B^oOfkGss2|m7AFHgn_>#|V=1Z?jJW*m-zT~GXVXO*XQcezh$&VKCrtW2SDQylCDEXJ5jh zDP9G7MDx+j)RblNZ>9}(qxpnoYU+3|51Udrnm;M6p)tl5tijVLt~;+GUDP!8o=5TD z*JEP&XtVM=Mo=at*GOF1u!^IaoFw#KgES=cnl`r_H-bRY5_bppL@C84;*GTj7%rFJ` zzTi2b!z}ZU^ITBs1@9DYq#e1osDcxo^XbivG)Y@gS$5<(pLW_nng{)q!SkN;LU|4J zG+=>py4!P}sj{A$ZQP-(s`H%RD50YX{^yleg`e|b(LuDb!XqX4X$0>W7D&zwVw4ab z!MC*upwquvlr_Ic@W5~VY43q}C9qutFMHmXEO}liHB=G&^c)}hs^?85+ZPf1;y`cG zjXA7@-gw5p9j2w|U)Cv)H$CHf)?*J&oTw}x{fw8&uA!Ydf|Pd+pYg}j)b!=@Ov>4c z&-fstn);5dsVec|DW3;jbj^~irug$udBO<1Q~a?heC1Q#F;Y#l0qJLI6!)Z(**rpYZ9u0_n`5SoXTm6aFMTh?ZY@!t_rc^SEchw6xS^ zR-QlRXFuquR-fIh+vLamM_5mF_LFz70dF)W4?B+ zk?Qn4V=8*%5wCa2NC&%Z3a`2G5x;uWNM}lRSG^qdh=-0clIF%&%8Q1Ncyvx9-JaG& z*c4-;JB-xR^FbSx0p}j_h*3H^aQ~R%yYeCL**cg;y}zxj8~Bhn z`aXzqZ;Vui_~88;0W`dGf?_W5kbBJVr`W0%<@dM;e44i(sq?>7S|549N96RSr_uM7 zrt==~ytlonigHHj(e(ijxQu=GWV-*HHfOu1ejf_j$Q+ zHT9_DtbEPy^StfV)U5t|)tpK9`8SZCp^MvX-`n~=kM9f}_1YTKBCq>A(_S@g*Og^X zU)<+C{WR36dT(~|`aOOmr*Z zn$_|l+gkA+pVGmP20VJn4!pa|>uvIy*Hzt+>m-t{p^e*Sui! z2j1nKe+{NL&2O>xK6m*S3w2a>&k+_;{4T#ZM^6u?XyV?z%0189{K=VM zx)XaviOqSNZ~7yMt`vTz?7Du7cQpi(e}_1w`ubbE=~n^NV6#OD9&w9*zu%AUm5x*D zHN3^^{pw5aCp}fRRlLPNXnbgVg)7R4cQ<*EyElEicaO66^iAHPo|Y;PT&DC{ev`NP zRYM7`Bb3$yZ}JoO)HE`Ply*KhIsK|8*Tq*<-HYGkR|3>DwfH%&9xre3iH+1$X=^i+ z+u<8Leje<>3ptqgyc_&=ehoc5)_@i2dV?R@t)a+izq2XTZ}65gVMpZJz~<$@!H-V$ zrYjqdvN=z#^R-)i=y1W?EEm7dPel3B@Dh>i+QjSpHx=ZGTLOF2;yT|oG=NG4S=e5W z>%7OYK)N^KB{Su`&TD@aOuy}Yz;<50#=lePXl=u@Y=77_e!Z5S2B=Mp54*-^eP^KC z{pYb^4X*JTw+ytRT~D^8;x)duqmk-W|BiKkca={v8>!{sWv2V5uJU@2pYPeDt@oB* zS5Nxa z;YzMUSGey_Iy(BzStZxJE8Ltrm^9NLD22LS;RQ|wQiG6}N|EYUc)O7SG|}6l6|J z8xBlYA3u_X?>NtMl93vD)MSSzp68908ENB@JEr~3&-1a^ zccU)GgfDSB&nIF(j@J08dgeIKV7WGtj{UsW%NMvi@~Ph z*U_bN$JvO*C;6FSda86{BlGKfl7}`j(2~%pY^?W5UN47{x^!;JiWfi0e;;Y2U-so< z4x@(&^pt9QmlM3MH|)XjUdoxDPjI%` zK$a}Slmod>aIY77+BZ8?8FT+QUz15sV=C-cnzQ5FGcuT}KDwl=nRuLs@F1G9;fXS& z`EgGD0%`fCSml!Iael6H0F@83D6_I2=Wp)&(VUZU%C&39c&P=xv?Su0(l_iFAKc!D z&Q!Uk(2!%irk^)$2->ey4nD>kHPMpiu$9WWa>sbb-!*h``)K9McSrfdC^gM5SXU{3 z>L|Z75`MGDC#s^0kMir#TkdOfsxI_C%AKLl1l}T3nD!`tK2=R4c4lN5iy!3^vTCT^ z4}t7*n?bBfR%a*zZ5yWG8+; z!Y7~hrJ|9~*^Jyr`0~R36um8;{c`Ux&(ku1`VP0S;-8M03I>-ZlG|+F?W+^9o9ptR3o_cz1Q#xu6@^%e$wEV&;Woxm6 zeAf@bl%Pfa%$!bx0%s9Z`H}$8js}dCN&IkC>{Ca?&noDXlaD!W~JBm{e0|24K4DYuAG^$ zpU*3!p`uk{ks(-#?6vkx8j za6ZvMv-*x@&3@j)!+tQ5ON^S0&%K8am~W)vd0(1(-QCS=!tUF>u88T2ZM*qq*n_Y8 zR#rV8zngEJjkB-i8&%`xyZN!QM#|sVS5dj{=7okE=vl~kWnkvrJlkeH={B!XvR>ZB zPjDTnoDM0y*X`oB7Y38A{tcz_kX`&@yCA9;@LYKrxQiDl5lAW>qij04lV{QR(%B-9m3xbJa;IsWF@ITEsyPt4&>7M)pXSZ^o) zu9TL_)mWr>e7h6tTtk<1gOyE@W*&V~O{U^5%G5n(z9mFWtMl(vot$Ro8z4XLYqeeh z9n5@cOEuka8gDvCX5MYBnjW?+#75*c^UhT?G`3$`roGE~^c@XV@R-T+ZsmM~SxXbn zZDG^Lah_?9H`Nb2$+9-*y!>Mys+jK{`^lB_)@A*um?esp$jteX9{yyxk-%15+`*rR z2hg%h32fxr9o#ol5bd}h#j+3C!Q0mirb01y+0(!sT;D-QmSHDZsqc31CY|-vXyFz% z7gK++o`J?%X0Sph8PDuKZlB_WI#gui9!xv{1;bs3+EJ=pGW zu-DBZjF;VFq)hd8sTxI^_%Nf9W^Z&+rtdNF%m)lK`r2Tn&omPc&1|5f0~aZA?M(b- zQ9UgkWmeApWa92$>Zrld3re%xCZ6Sb5WVwwtkk+2&NI&rq&&}Jl)hWSc`LsFdNIqQ z+#eIp&pY{3xAyT$$7bRD`<=dY(CfM4<{HlHjP#+wrEe&&GKKS59lYuE#e>S$3)}h1 z5G}PByhbUvW;?&N1b)k^&{+TLZ2X?By!QrQ%DFCr1y0+_k0tn#u3S9J z)^02BS0jK%hFVz2k6U?`ae*|VRxHbudn=!GGKgAVea!0K-NLVb2qx9$i>%a^E!-`S zo{p{D$)=3n!pFSUlmD5;tXtD9e7)H~og;r^IbFB#20=zT{gpe5$+U$x*@!c-&OuZ0 z3!8aa%-x)wBf|%*+RQT?Hqy_hhN-^zZ8LxQ8#qO?e9GOx&3s-4BfT`WR92PV%p3R{ zXv@UuN`v@Kyn7!#73i{A*>P+W|E{-=x(`307#3~fBmIKuyJ~lp`5~Kl#oR$uv}csk zzs@EebufU|Zb(pW7uv*+{_0OI87&HbzLBe|`O)+C(MpRw8@Vpdho+ynr+81>$nPJA z-oE;j(yQ%8e(jK!7G~L|>{o5%W1qrLvS60da(u+JH5qrcEpJhC4Ocz_a%NcgVlpwAy6@e{clsX;&o{muUmP)KEi{ zej30|onOzt{YFd2A1+`&tX$9Uzt>U|7tV70x}NX+(uV@KooCwu*Yi0)`qJKBkJ!@E z>-o!H{owzJVTa#l^)N+)CeSI{H=gAXD<<`Zsbqm9I(S|`({ql1*B_xc0JuR5- z7rMzB)CuEVHtMKQ{=@8T!7$!tm7ZK;*D}9|b^Pl=umPVE@yU<~wa2 z&oKk6p=?H0rtLc31>B*>pdU@Yc&+0;;1MgVc%Y8mIWJSi?&u_*3z97G?I}HGI=LKMG$Os{{tF;Zr;K(ux^R zl;x$@@VC`4R=Y1LgX3276Q#Uq>#JSL@x!b67*8z~Z62yDU9g%5g=nbt-l0mXkk!1* zHP{ZXJQaPN)x607HTi^`RP`*lnjaBoU(4lQ%bu>{9^gu@u6;~?yI1jkOVl)@;n%Fj zv{n4O5*m7x(3E9wyNVY(siAUrr?N$!tGL^8Eq#+|6T9=}D&BLMH+`=^&X(O-$%h^B zq4z;|*!#^Zd307kTKXW8ogKN7zw(D({c8d%+HfWRes%yg{NBQ%tE}Yv?gY}xhtX_% zrj>kjsbG2(dY`R3zk>Jh(UHfg)9k?V6}(@to;2;Zv#5b9cxY7vCDfS176z=~zE2HQ zvT+wStMm$9zNeAy94pRR#4YC@;C)}zm}`nTw47Ih4fuPFP|phUmvb#MQkA=5Doani z)7nUdj+Ijkb(ZrB7hu27?xU11xSVe)Y@nh3^Oa6dmhn^Wda8MeDL?O8#&4C=(cA^+ zl&_{O-i zO<(fs^+JieC@i38}o4@7t=O6^kb+ z-kFy2D|xgkFnUE>QKDMEgBFRG!gZyHNB{bHe-CMaJ?HeIfX znhfK*s05p?0Q+?0%_ z$4NF_Z*mYdS@TS?=|KnJ-#c+tvgw>Rbu{+kKFOwkIHiX?Um@9a%ee-+`sHZJrsKVg z^z4t?l1;x_Vx-I$9-0K3z6Y65`Kv4@!KP=PGE!gXIx4}Y!>7W3tI4bgHl4dTel|2n z5o|h7UjwZ^J5dpAx=W~@wuP@#1eI#xgckc#2-o8yL!KSN2w)Z}A+f%UV$8FS9 zujx#aVAD%Bt4aI#TPE0aO%?2#xt*9`(>EhEqzszP1e>mK5_a*fZA`G~8t1)9UH3E- zY`XtDAA0-qeaWV;k{|uFCR(!TE~EX)uYg6e=^3X2DCevM$)>jz4kGt*QIbv1Fa*=s zop&UgZaqjxOYa|-YSykC1G7O%EUHe(aiL(@hQD)V$~c$)>$pYiVltRgz8Tp9y>9_!!Bi zbH%CY$-w%OP5X^e)3>i)s05py6|AOf-SVpho33I|QdS-vjU9GiDu<2Rd;phML5EE>=+(aMRw)BQ%)AJ7cQqaWb zl1&fFM@J4LYRNi_{r=+aC@u<38x>gj6Zt%_jNPAzp* zy~HU+uxW2qFl}gePqJzAt3YZ~AzHF&?S=r#_aZ^E>F+!E)5?Phl1*PI?nje1MoBiE z`?e367u=O>db`P+{PLWXY`V{OEsZX?MY8Gj*ERIUFhjEGh7~jv{#$FwrgyJWQ;oU> zB%5y5LQU;9jZz6V{TzGHXJMCc!KT~yR@0s~drg8(7d@+{DXvwSVAE6DLO1^LS0>oB zxvZ9M=3C4Jn=YT*n}V|MWP(jEaQ2~zRWCBZru_qbsn(Fkl1)#X;YS1W#!5E*{VlN9 z`4-8h_mmB!4c_sRO>4Rb(dE|>l1=Yf5lnsuu1hw3c%P1PH$5oXbac3$eu`Kv*>uJ+ z@H31ZC)sq*ibg7{_m*rrVlK|#A_*qJrhA-)58>Q*Cc&nE$LF>IrB#AW`^_^_heq)# z!KU+7!u-D0DuPX4$M4+NVw@t_^edB|>K|FH2sWMJ0Af6maIUN=?(j?fl26H{;VSXmqbZB|#X=Ph8!KU|J)6m%;W-!5~n{R_pIBqi&Y`RCd zH<{v2Fu|sm-}E6GcUQ7$Loq+fzbs0!=_T#_srTLl$)*p51<>v21j(k!5=ebKq9vQY z z)1laFFCI@a2{wHid+_^y6}<$TF1F1`Ke#iMVAC#*;d`%9MG1~=^+6@rbRcBrI;EOQu<3!2rI{k~ngpAU91TXPdSMc5 zx_hje4wk6T1e^YGhK7cOj$wjLS8at@AfHuCuxYG)n(%Hv6KvY2yAQc;xhC24#O1zp zvTlTA(~F<`(R53kWYcXt0w`gXMY8GJzXj5{-(n@3KD0lGPWU~MZ2C@oFnKk)B-wP+ z9C}(aV3%am4`TH6^w1K?rh~%`@I?=mYGj4(Im`SkdBRKmGN6iTr zY&r;M;)Y&>RDw-s9B!n7cXKO(P5V0;DO>yIieS@y^#%$VIZY94I&83>3==jff=#a+ ztfO6rk1K*rzc&Wc%2jtHn|3b}L;*#kB%3aLCV;w5O^|H*#Tb9uQrIHdbmQuNh}nyl zZ2G}_A2J2qmu!0c1#j|faaywJx~H@ha(kO((F&@uV?*nj1e<;bU3Ag7Oe(>q^`V%@{0~)v zO;1%Bsb|gFieS^8^KiD_8>I*~?RHvEXO68<1e>N?I_es}PZ4bT^1)#GV%t^8rg#1h z{d3+k$)<~G!OB;}NjB}0F@T7QUbJe|Y5 z1e<={SWPptb~Xt%{VQyZPS?IoHtn=fOJ|%nGQpIMw~PC7XW!)|U!RjFfEpbX|XX*EB)0=`521sN9bh$)?v{3Z$!5 z!6?C|pBE0M-rqlvY?{~BQR`u6B%6NYt*8Dq!zG*cuVkQswdP7Tt$$#kN=v&*Hhr=y z{CKrXN;W-fmytH>7McW`t^xb>@y0Tqf=%b+&|6NfQVBNA+96KW@Vz3~bo5pH9(^xG zu<6nz5OWpyha%W?=b!XcI|GB=dWWxb)zOMbFiNoLubdF;SmmK))0g%J()^=flwi}P z1_aQl78c2-uekWrANdm`oA!C^OS#XykZgLxS|2Jn@0MiKE601&uvgz3k;e*X(Pzg324EwY}!~5ZaO}h+1 zJkRqRCc&oN9wFwcd37e(bm8F|n&3Q=2{v8QM@#qWFK2>HfBU01dGy%J1e@Lw=tG&d zT#;;g`6zI%h^LZGA3F~D83YyyHvPCj04+icwqVnFn+KA+5+~VozGXqQV#ia-rdM7G zrijj0B%3}QsiQ0T_ewVHbyH7~*Oo~(y=A$9d_zY_HvOcgkxqI4EZKC0l}4Jl=9)>c z=^7V}bl&?~xM0&io`9Y+w~$<2x8=OxfQR!KP15 zLrg4eZNa7^X6a~lo1=?nJlgIU2l1)!mf~ec;7m`iChz=mzzQnKmTV!reyE|E=#M|;!TMQ0_O9`Q&^Cl;C{n+|k>J$P%LWYfj88X6ZE zBH8p8yC6TQjAYaOI$<8iu22a!oeT1FAszV$ui=$WYa|_LHDbDOtR_U z#=}p$V}oSVaV-rL+G2`i)7NtuY4XfQl1-NxYov?jFC?43bIeG22emT^HhmNG`2Dhd zUV=>@UyYcYeHT=MO^>T*q;~^;R0NwYxz0e*jfN|NO@H%HPos7(RRo(Z@JdH9-|bNZ zo34Ey>?Z88WYfQIK#ZK~sbtepodW5mC04TOr6mKX@Fw_X!KPPV_M>&b$4NF_VJc!i zJ3mtdn{Ly@hq86QD%td)I^Oi8=|0J(^XeeeTC9+4dhS>ay=XT|vgzmW^X#osOS0+b z@c(o=cTXkQbj~2e064w%5^TC5{6%N0Xib7mSBD?z%AqVwu<3`0^Uw69jtMrse~X6l z_MXH9n=U*?O9yL)F~O!E5A~*Dm5(sNruQuNp>~lsC7WJy-Iw&OUr07>`OcrtKZ=)Z zI-qL+eF(8gHtn=MkQx??k!*U;s~}SEc_`U*tFk&u*l|v>=}~TaYWIdoHa)M9fyxh@ zFWGd$c>`sA-AA(N1+9$q)V;i9({D{is%~Cy5^TCGjaYeA{QqK(JXX&g6Hoe)+KwS&WQ3RVd>F{@JZC3=Fe&nm8n;T9mf=!qCE|_*q zyf4{w-+O_y^h&g3)7R$&(7I9<$)?u_`csn;36f1O$?iw(V;9kNc_w zo8AsT?T}YX!Udbo0RQcsStm?_P5*ioamZ6VnPAf$dTMCd)S*nU=?)%R+FdP_2{t{T zBpCO_T}-g){_Z~1Y3U`&rk}O*rGQ~iB%6M_#*f10#!5EbEzX|;*IFc-rk?|8-Q76J zrmG@|=-WaOl1-Q5!Bnf;HOZ!rU(nJ0(EXB4yB*e3jk_x)n_fH}9IEUX$)win zdXi253jg^O%QKT;)0LpN1hvj(5^Q<~{Ovgps8oVY{{laJl^q!r!KTNRLQIGfpa?eo z#bCt9nI|ZMO;25|r&1@@DuPX)-lU^aF^3evrWa2Srm635NH%?>Q4pOz^jxy(!+8U# z(DHc6rVU5^spA-nWYa5#_|fh0F_KOHL|D&b9!WM$xqQg`+=_?)Pz$^u<7s^ z=vUkBNj5#h&5uGFMN2lF{}+Gy`dxx#)5?JWn!7bYvgv`jf~fs(QIbtR^9iP*K6fRX z-V&mt!%I#`HeIc^p0-cfEZMZbAL3NmbjhYqelSqM;;kf`?gDOA`Di}LrVk>{f9>kw zCc&nw!3HGbFfYNTw}OA2=y*US*z}tq#3V0uQv{oyxzj+cCjX`gHog3fp60GttOzze zBCnqMjohgSHr+g4vY= zwDXBZvgzC4kB5rHssx*Eqf^tfgT+;XP1gml!~~lJo1Tm~|A7r(nFO0Y_D)T$+WIiT zrXMcWP(YUPOt9&}J+&08Tf+pKc5m-ZBeou7f=zE3?nAqC+>mT~AV-{4+2@i?7t7*L z51PkIHXY^zjxYzlP_Sv=nSm4$7bDqp^Q%Er%=@uq)0=Z5w(8*p$)-b#=&9;zvt-kw zGZ_$%v`Dh)68jNX^W!g)P2WYF|Is3@l1-mMoc{sm-6p}NM`7*;&1e)Z*t8DZS!Efc z5^TC6;{2PnET{-JeF>a;@|ZS?VAFT%8_0Nkh9cPX>@JAu8n8tXZ2E9V$br@;6~U%6 z)efewuHThx`a|X*I(#uIkxjDz`ubdgWYfQe_*2ij36f10Ebm7zouVb1-v7jhid48K z*>s=1-c;wrNy(<4??h~sWs79f@9t`-eyf?1O)EcW$o*Pd$)*#){iBW-l5F}k;sNU2 z8Ltv-dO7xB%U^4U3pU*x@dMXYW|LskK_}G|vh@ch*mRW^@Q23^VuDR)FR7&>1s5^F zrhm@vO-5HU6Kr}!As<>l@&XfVxb{pi~17|Et@p7*Dh(=3urw=Nb) z^#{aDHeJ4L5anw5T(aqa1;G^8;)Z0?opyljet$@^>1!MHwDRg2$)<}9GfN`ZLEre8eur=aB)$)?*c_M^d#V4Ft~=t}%W$)?rcc$3e& zosv!W{{eTGsx6Uh`gmu=>U0_++4RthYATqcnqH8lz+shO(*Zd9hCZC=CD`;~ z#Q9I#GsGm=bZNx%9Bi7G2{wKDI}Keq(t-&#J@f)%eo9Ygf=$PTY3Xd9%}lUq^LlUk z!RrJQZ2HxCAA0xpj%3r{N5tDC^DyEH+v>F!Gd=w42XWYe#n2U4~%(UMJ< zsuD~SGvAkNI@+MaU9eM$O*^*7yih|#AT1UyI%l5&%oG2>U zbWy}p%_}tBB-nH&=r9f2WbzVhI#;+6cPh841e?BxxU9&%6&1mzr=K#Aldiua*z~2` z22u}Qpa?cSwxXUIUfrPxHeJ5Bj&}4ouLw51EHa2RwH`?}-EVCmsoKU!HhrK~00j=U zNH*QHh(Fyo$4fR%XML&bhv$+_XPxas&2%>Hgv^JZD2FwVQY`PWV{LK|INjB|`xVZf@s;dN>HbWQnpOM`p*mO6<(Pb$3#3b0X zTa=o9T3?3=Hr;o!hQ1m*nh7>twXv3RH(JRAo4)UZyNWLRnPAgVZGEVA{%ev=_xl4e zMOU9mHeKf)?tC4LlWe+Vr2x7TW|3@qbe}+)%3~#)KE{IR*uE!{O>cZ2Oc^p?mTcOP zQBMPXcS|;1_&M&N?G2S|`t&9PEp;Cz+4Ov^k;=q+Nj6;wag05GIc*Ybx(R$}KTHS< z7i@Yy;vSzC=&2HHI?pI0Ju&7|1e?y4(@0yhHdO?hUe(w@$NElH1e?w_LQkG6HY$Qm z`;64lmpP6rf=w@O8BAxsxg*(h*YAQT|K3Q+rh8vQzj`J}HeF{L;{2;vB%2P^fPp%_ zlx%u!c3(Pw`MzY+ZExc2D|AM(>Dw2zG;Y^+$)+hmLnT+uk!(6E;`~?D?<(2!@a@=x z$4W>xy|*3o7T-Tqf=w5L{LH+6*ml9D{Sdzzcwwzcu<7-C@y>~|Ot9%L{u(le^=5)i zXZ=!36`%aU1e@+2sipBl7!z#z{%db4+5mTZ!KSm7^CdRmp=8s;JNZ%3IM{$-)4x^s zr%*L?7_e#EJJG)2Q}@nHllPRN`~YruuYcNHIlxew_tzWv*T1=Y-*E>Jl!vC zH1xwCH{|DO5498-{7QZ<7l}IyEwcY8eowbtxMR3CkNi9b{>*h73d_%V%KFo6=Wpd_ zaW}k6>EgDZcdR+JjMv;1NM&vm-C+t{#+$bbra3S2?kOnTG%nq7>vV93!9BQZfZ*;BcbBf5O+ws=An}A4ad#xiJzal#_kFzgJ#W2O z8D<@RIn`D5Rek%8J<*O{$v^a^NitxQJsH`&lD}`Lb+FUF_GD%DO8)ntK;Bp_d$RE8 zN`C#*WlTo49a#`>#UH2tka_2BN0#T%cQY%(nOA4*NFvQWbCoKXE#`LQz$Ov@#x_;m z%j4|Gu3U3|U60e zqpn7=Gijvv-{=~3j|DiB7xejax<*~YE6(Izf>63f=8csz+5C)V&@D;K&8g0$fI8AO zGK&?QNmJHx=^B}-sZK<&ak+Gjysht?$gEk*rEAn_IpRcq>MxhBQF2(%iS+hfE?px# zey9`avv!4ajci?&Bk86ukgk!fe(y-G?h#7Y$ok%QB!!XmcXgX;$d_%7q?EpALDv{k zFxQdvuQHUbF{Dbvk*rfNmaZ}6Wu=2`jUfUPcXSkwaYx6PW;b+v9_@yXwNKp8F?)|2 zI^J36hK{FtxuK(fp({Er4Rl4vi0iKCcw~($Ixd*%ijKOSF6gNEg+8nE$8nUC3p&m? z=7Ns8LKk$bn(QK5qweE7Ug+qs#S0z#&GACV3Ng!pwt~5&jh=p<8>Q%bYynB%hnk3 zJ;fIto9unjaf`JtI`UTdqT|g$zUX+Y#s?jz(P!;s`*F}cA9OU`?1PSlb9~TogSHPk z_Q~}|#~crDbj&#GjgGG@ywNdqyf-?2Z1Y0Lj5sfJv~l;6tx@-%UV-SiAapz%6oiiLH-ga7du9bu<(m4+%oiF=lWmI{MYVN5}ud-=m|&{rBj2bIW^l9IEpk9iMl5kB)|UfQ|#a z03G|B2XxF70XqJiK%Y7P^Zls)lb~at1cHtc9z?cA-F>|y(D8IhI677bg`;EmwQzLo zzd9Tp6=#H_V~|ofI==h-0UfjKKcM5TV;|75+~5N`z8L-i9k2@o3z8wv3E_VY>gpc7LAUHow!h(Jwm|9bbFLqNBydSae)y5sQw; z#>S$f#*Y|ur2Qu7$a@`wj>`LE(6Mt-3_3>jk3q+h@@RCV2{t-*-iSs=uf5T-HHNJI zoQRG)oD$J7^H?G}dI}TKQE_M@I#$;uprc(x0y^G$kbsWSTNBVx%u7JWuYV<=I36AUofMCbi+{zTqhVqkI(B%*$=0ar(kBHSgG-aqae^cn9e>*- zqoc{1WOST2GZ`K0m6Opi_e&Bw_H#@^M~CA{=s3nG2_4f%B%$M*x{v7if@T)7^VLm{ zKceHsoixArbG~|4_ai#K==KpE4Qmr+YYb^K|BQ}m6F#G(^^Z^Js2~3c9bdorgpM~3 zd_u>COFyCG(UE8S z867M3eU_~;Zdaj&Tn&&{1)F20Gql zGSIPSj|_AS&re6kn?C92c(c(2?hzCR?L!G0pL1 z*N+WlIq0~F%|XYxH*(PN#@ZZoJUS}}9jB<~pyPnFY;-hn%0|ch6WQpv&Nv$#d;Oh_ zj@k8D=$Iang^n+uWTE5xU0LXuFfR)o)Bnms$E$UjvNeXx66K@gqKWzF==1X%I$lZm zhK`vpzoBE)!Efkza@jX@+}8gaI=(8+L&xbMdFbeII}aT(1ajZ%nI#y=n zqGLDrTyz|KIu{+s8s(y6+KgP;8gmfW z3(+yavJf4s#}}gG>0brt_&d1(9X;RDXKeo52RL@H038o6EkH+RPysrwuF6Np9gvTX zhv~C4viksI4&=+$7?Sd}1Re8SO3=~hWC=QsrhOf<`#DF4m!RY3#_#AjF#0<>DnI^? zj=KMSN5@3n@93!4^E*1W7ZjsojBhbIMqDaJN1K(jm*dZU0M{wS=or*qgpLtOMd*0Q zr%1L&-QoQ!&~a)-IXb=!DM!bHH_Op6YF#-x`phmz$L(t6=xCN+hK|>r%g}M~sWNnY zYEp)d2BXT*v0q~;I`)bxMaT4~rRdnUyA&PO=9i*luO6l77+zl@TVu!`%W8ByHK`gM zD}T|RoIm&F!V;^{vG40DbW}K8g^mHstI+Z7fGTv%EUQGv9i$Q+%kEU7T!}I$rM8fQ~vv_2{VRUyqLMm+R3nVpTml7Ei55$A*qNbZk$qLq|{F zI@ua^R}N@J$L*CZ=$KAg(9zwt1sxSOw4h_vKP~9^R=ousZ8MtDG0LSG9Yv>`(eaCE zGdf-w-HeVVO-<-%5Z#21y`MLs2j^yl%x0bj+qbam1tkK55vb$2^D9^tp6qp*8B zI=;;RjgB?}ztM62wcqGCY2|Np+%)MoIySWbLdOH2exc(Sd-~4BpYO-&!@tn6eEBbQ z^cwOD9aCz4qGMj@PjoE5^AjDP9r`I-W5}r83LwinCRr+gEbl0suK=>+s=;^#kbOT| z_f!B`-jUJViH^3ho#=S%X(u}R?CeCxMe{q+F|>ClIvy3b%J6|J-7)6lf9WT8VL6&#) zd9Dbu~R%R4soRs@-2)K3MF-31rugo^eVbyPtE-R|#a- zkJZnVKz2W;@}d&Rax0^~N+3JW$rCGq?7Cy?LM4#pR+ST!K$crA8LT8*qwW&}Rdjqa zM-?5dMyR4=xVkDjR@JGXbnlOC#|n@ocCX zI+i=Bp<|!BYUpTlQVku8x2U1xDnm7NZ24CW9p8^oL&tXd4ynvBjlM%FbJV5pkjfl+ z^c_-};|ot!be#G`6&?M~siGrqhblVWU8O2pqi*R<4Roxr)<8$c^&05dOQ3;{%uEe* z^d6#tj@qgk=y<+b9UX_IsiWifP<3=1AhatudtgR4sJuKR^o|lR7ogQKw839XF+FqGLt~eHZ)B_v0)FO>}g& z)kMdo)|%+pZG$E{8t7@FN*^@P@tO<$cm9(j z=RebstxP1qhsf4ZFF3Y1% zIv%RfLPvwoTIfi-*wE3-UJD(2-_}A$yJK4DIB}yEI(iAU&{17ii(8|+=}+b+XhJpL zl%Lep#@vk4gnpaoJF~+Y81Ju|Kwm=RCypv%Dho8>;sp!-(^X%YX*HUlMxWcfGbD`J z{ZkW)X$S8l;>bKw(*i5{+-9Mj4fD3Q7IdfY4c+){#@rgN1!f9X{DdCenGKV)V6VW6 zFKoWS8!|@=JpZ%eUp#OyD14C?tX^-$ce?gmvdT~kY$jXr2VLvW7F%h7^qnJ>%r)%B zE%fiC@07iaxXq^S(}Jz8mi)awp6tITwctpph_Cf3p1pBJ3-}r${<-=>_Um0O7~a!@ zuRFe#?e$U%ek+^v+b=4IEO6F>LFK0W%DI{$8~n6@jWppOc-bxF;Cn3?^@6^i^6sw? z>o_fVNZ+wK`fs<8onN$IytyHNt&v8E@i#4)J&*S3byo@*M~%ME)~D~&HL|r$TJRrz z&&XkS9_!Yr1!e2$Ges3q>}oA-xbs55|Jcu!RqUq?+HEWN?xr``=OeVC{m=@2iID|6 zX_7Wv>9vBNCF;(4{G$zVsmu9yLvKh%EzpMYfaUy4H7Dj?6KaE6=yLw7_~*QD=Gx$2 zy_|owsy{P!oi+#;uHc(1u4C5yrwzCKSMY`X?lN}{YJE5~@y|m#{ zj3FP+4b=T4(S{urMtq%JLvM0(8v<=$Z@AH5Z_3E(E%@75pTFtCXJ$!XEr_w!qv+d~n z;D4L*e{b!td-aw!oO^A`FP(Ofl00w_8UY;X<@&?CQmKwH<w%6ntZ_L29-Wc^mfz7dn} zs@OMD^-&f3M*M?R(XsKZDms3=F7J(*c}U(HGkuM`H|E}Qd2h_<8S>s3*MaihnCXi0 z-k56*Dze{I-P^?~*f;VhNd@~xjDl3qG5EC#Iu>4&_y1TOlK21kt&#WtOjsuG|B0L` z@BgtKAn*T4RFwDsI8-QO--y;{W$YW#Aj;^t%TXB}f8Un(|6DjG@Bh)*DDVH-U?%VX z*}hcXzChl`r8!&P$F*gsypJnOMc&6{U9Et})%ocPcw9aGK>>SX z#I6eH7;;bE$0a!_@8cS}P2R`lVJz?C`bS6J$0Zpl@8jy-Ti(YtNJZYOwlJp?`|-Rz zIIQt?w)E zRh#g=9edTr1hr$YTE&fa>{ZiV-;TX%gJ!g2ui6+zd9T{nqTkr7RuuCa`|;|Z|Hgj2 zjeCA$Ki-`Azp)?Brl-6g@5uLG*pD|k_!su$^|$$j{dh*Jeqle}x2f`eytPX5e!QMv zequjfmi(Kkxtm*LYt&t~q6Hl-hRFLWBdeOx z@hLQ;W7X|u>^aQX(u|I_bDPoexQ4v1(kHVC9T#~tVb5XM`6lc+JY?R4j`POI`zm!> z8qu*Mz7ZWqylTXr!>Rik(NSk%BRZCklJ`}%s>yptRkIt=@rZi^?nk}T4e0pNxB(q) z#>jg|7qr%+(j)Bi=aX*gRU5k#t=GCI3aSwTatZs1)I@Sf&pkvO} z8r+Y4SJt4T{S}W-Kf9%&!)#&)zt{V5_^CQ*hxKXbf9WM-%_s8C@sY1u+p|q#> z&wkW@S0!6x$jU2KxF7#pRfUcjljS|Y9=|KmQ6ae!9jojraX-GZu0%)M6_w~1HBjCI zEUKzN$1h&B1@1?a%@ycq@NWe=_STa30ME`XN5@5;<+vXW&eFc+KaTAi%VlfS z)m~nXj)Mlv`YOVH8tZ+V|HQI+>{CuDv{M_sq? zxF36*`i_p9jlQF!@o0H3w@OPfI@U!OqvM1p#ke1XcNL@K+=a#HSl&zC%k5WKgpOYR zMd*0MrU>`rqcuh7Xg5{f%k9-c`_KP4t}iG=$30Pn=y>XBA@0YjorUQ5LAMYc`*xT2 zt1A>0pkrV_0Xn|DQh@t0Q(Sor8{Q9yz!l zd!M262>v*RZ^)6YQ8#624my4tD4%y=T#=2AqeHUM@u+P!?#IoWve9wizuD-hq9&hr zFfTm|9TQ!%a6jsw%|gd^lPq+M`8x|8BN{W&(Iz$%9bKPi;(iR?or#VS{7iH_JW@XI z;Jk`_ZpEF940Kd*&A|Qm^+X0bPB6?s$G)TFb1UMT($O&>DjglGAEo1dJhL+$9e>YH zM@O%o^0^hq3ewQ=h+i5yGS|{@KdxDwhK@U?$mdoZZm07>{y2`!|B8;YBfp~Kq9b2}Pv|%f=$w~7`!VhHC)pZ9iZ6b`{n#k}gpQjh%IC<; z{h5l6Hxg6P@#x!B+>cWZr=sJ)WvS?B(qBGDCciud9oN54LC4;AQgA&BW@+5RDmn5O%yqih5 zA17=~LdU$>N$41-BA*AOnD!AJ@40-${n+!&M|6xZ{)mpYBjxjeY#I{L(I_Sn9rr&= z#Qk`BS0XxIo0o`=ybI)?M((eZE(`CO;@`ElsT_{O25!qqt3kAJU<}Qgu$A10fbJiToBG7RRM4)5( ztq9zYZ`VhlEBhoj?;{_=Tw znWZ1l(KGl1Ix5}xfcvp#{ReckoAm)5Z!62^<;8pnLr1Z581BckQ(@?M%_s~V%|^)Q zohn+v^e91qK-nk*@`2Ir(Iwn30!TmUIdk8xA(g{Jwty=Q=m8RcVbX4bu{CFpo`nFJl543y8WbSMu-M<15X3H`Gl zH@*y(tubWZ`C#0SXGFp1STjyOhcvu32p#*!2ce_V>mb~ZK?j1+(Qa`NI%fBg&mrAa z8i|zhmOOX{BS=$Kk0{# zMuvXqIAFMZo@}2wUv$ij^hL*?k9~1JYV7bu$3BcNIz|qa&y)S6AfF4I|HTI#O&oo2 zKaM@>gO10AKIpi0xO^_~;CgR#R1Nn=$NBfYaX%()^F~JlU2k;k>?WTJ9GB~bj!|A- z=y>Cj7w$)Qu@^c@CdlUkNByAlm;X2($?-(Ti(#JVc<+HH?nk99#JMKs8eeUQuZ>c*vt{ots z@4Tzb4IQl|bdL6){W$)Gn{16C|D1Ef{kX)!4ITZ)%I9=nYjH)#>{wTHjCtvb`|IRbxRgFqhnJa`MmWl-<{Br7wCkJw%43+KOSG}gpSi@IHBVpMftpS zvrmrbSm@x0`*FhwM|A9C;E0a7L*?_NudI%@Fy# z^~as|M=SoF4KLX_6?SCgvX%T%%l>0)!|lj%-b=;+=XOM?Y9-%l!Fq|JwH-Oou#*2UUYR$?%#O^8UdcD!-^6Q}Vn;N$t>nL$XU1r& z*^#@St@xb-?=xO`?}$wwD}Gg|gc%V0j))$M`HqJ^GM0Ao=N6>TFa-S&^ILBQGSbgC zoUQmOCv3RSzJpfs7xkLWeP)F#`2%;q=1G61ea=cgZ<<}O^m9kP75~TCDv9)S;7Tig z*moiKT*OgdF<&|FD);$nu_b@-b|>!hl_n8?b!<5IxnHRTf5^N{?(>!p=KQ}#RB)f$ zY|Qw6Bb&L;)h4F=d$m8f&-A$qkUe)%re_MtcK`dCQzy*e=GChI{rod?FnW^9eIDsx z0la_WxX;(_i6AZ8i~H7xk~ zzS7SXojN1iHDGG87*ury60I@~cz#z5&IT&1YpMpU7%GO2$L8#PRs*~bSwg>sx7Y|f z4S4uQ1or(r*-5uFK*h-d^fcnwsAC$i_NqCwead6IZ=!#Xff@8NtzjGWG{9KJ6z1o* zu>1d^S$~KzL>*~kSB%hr`3H@Foz%##(bRyw(+y#2W(oUWgF3uZG=L4cpV`gX>aes~ z4`jXcEj{%h#PuaR(_0;^%!SZvhc)~4sXA(kU8oMN{sKrU9mX*98G!k^LU?_37c-nb1F)k(2$4lkm?!iZ zfXS(PU_LO2*;A?pAJX-Ke=CK#lBx!liiWV`a53|MRfFn9Mi3fb&)l+8gG)DzVejxZ zW{<5Jczrg3gV$S`mB-W|VyGERR;^tsYtIQ$easgANrv{(SSU~-gM5g~gYH;O@ z2*#NEGKYq%fr{7?iWc2x2GaR2=hVb7FnJxbjn03Gz9@$03wknobpDHDoERqL9OH%2 z`7d7SV%Rs}b?`keRS5AEL*1)HiO*A2xN9he&x7W&VHfCJoVYnI0*K?4t^Lr%hqn?Iw2NZx#4F z+XSrK+Sn&0Dxg(q1f!~&*+r=;pl)vnI+Lr|d#nmH?>2x{H?vu5I~C|>t`CRfBiXW> zDsW(f9%T1$VS|sVKl+0SesMWlt)~J;R|T-9u1ZogTLtvY1u(|4 zr-U7*0=Fy$AnTw3=>?1U}AHV*%_$}|DDu>2XEXN z@KlDXgZe<{KQlX@Dnr>F18^zGW!_&FA;ryV6_Rj zUvFb_7bt_o-V`KH8X46|%D^i#1Ig=BW>6nx*f78XmNk80y8l)Jr?Dc?JWZH_?@ExP zZ3%jdUNgxlO7JYf5`Jo*U@ovqFno;|?!TSN?6;$T9w-K;Jec?3rV`|3h(R#(Z=C{b zC0G(E2B&}SNbb|z|J_kB#FhW6k82_?}U6!o~9?hnps$b9YA{Ak#y9wyGwXzzXiqLI~ zF-#6=Wm}#oLd;+zu)AHydR|ZjCdUB!Y%gSA>{5iqf%;$_{gDL=MY!m%2X~1dt43#O z&B_u&Sk(hIgwE31GeHRB?rdWF_fdp1&H~u6v@iSPmja}$7Xa8_l5F~}0Dl<^z^m$% z&V&>N;2jaboBffzRjdNM`YZsQsk4~_b_x)*T?pU)KFe&msQ}w2>4EyOx6E{F1u*WT z50lrvXNGN50NpVLAnT=HATosCUS&+|Yz1(5Y6L$gH!-C{>EB;u3<+=An91r2kTcm7 zM)6vh*rHCNf5;5-QmdGYft}=(n>qY*HHQ&i>m>bSETFbqG}CW&CxH+VY_)Y|p3Uea z=GQI3ckp#aUA2=;oGOOKb$Sew-a(q5i{ani&AbsV9VGgb82Ygzd2XjVhz|W+v17c% z#;k)Zc_xNMo7yBA<2uNyNn+Slr_YwRwiBBxmhdk5Iy*YPolFT5!O!t-?3-8Z#OH$r zT)iF54nEvYwmO)@`l=i@dwDzgu-gpo^sQ#!4s0hA$C|=IaSOYx@;7;qV+>24x3R@x zze(FYBbcYu#IAYxn|v}dgwBm+?EUS(iFmjH98*tYkMMqzsonL#;}ftyy8R|S#_7S0 zFK^iN!e3Qz4(tgbB^q=I;WFf@#-@^QGrt=5$gi!PJArpM^Coz-g0b}gX zOf&sSzK7_;-i1kw_t>B0bfE#jheD>Z^#|Gdw-J1fu45A7eh{*gelL7%WmdfWLGpb~ z;8bZVGxpFAV)WY-och%>{>y(5iLN=wdgo@V5%_8V zdq}yJT3bz8o&TInq$wZIIlYfIS%=N9tUD^t*mY-C5AY$01MOrZI08++Ecg%oKU zgZudww)@x?(kIdoMjWnY3tO8>{B;8ub|#l~j%y~T_vpiXgBW)8i)NB!tq1$m-P!O1 z&BWYM2)18uu;S&-q@N-^?#(e`Ukq#}cW(SxN z!O|#-Ss&0yR1O)yh{kM&cde1!bTx#4eN~LYszyTUji7fo`b_DRMskEPf!j`POgE)Q z^5dc@EZyG3xTQ6akXSSLIij3ta&90Of0{#G|8yqlL<6zuCW3uqLz&q|4dg)!b=>lf z=}zhGng{JjvcFAM>-NsAoEo#dp@t0q+K$G|9Z5stLcna zp{^0keq7IXyH-ooe;L52Va4pPm9<3slRk_Xkirg|QcIR4>Ou6?Kz4%y{aho2vAid& zLRt+`)DZ%x>}1QFYe=H60P24CUqf)7RLYoFRFU#yMljNQ8$xWxkc+`%}DlLOF0=E zVGa$=S?uGua`NG(861tSWY<40CrZmrVGn6$oA;EHk?qFtz^jd&xul$g`WZoLOcVQa zKsnj5*AN^t%UMxH8Ck1q0QRFY*oidLKR;d{79R;?_ueiemvr?&x!#UlvbBuZ9uY#_ z&I{~cyfSh)R{(Q&@mLk@GU9kb086b?B|~y)MsFg3=)Jzdi+oDSu{8on{d*s;;Yum- zdLsZ~?q5vJ%2Kj%s1Wk+uVI2Fmy&bwLU3Gik6F=CLMq3bT|`#$M4&5X*__KoWW+QJ zI5p=pD_L1Y#wnV^+6zgyBPOtFdmEdXT1ehcF$P&L{nBDX z*y>ipzC2M#N}Ubh*ZOblb^|*1{F*+D{}9Jk4KF08ZS|m}&Xd({Dj@n2AzWX4n{A9O zASOM8FeX#Pu6tfUHa(%oNgp+K>Yf5JVWj{xnoK2Y78Z~@ru6&qYL(8!{sm;@c>z3Z z{l@EFkxxFC3Bbr|A=91Y6U)m&xN`S0Gnmdj|7N5IGhG~+F`M#<)qH)h4G(9E=H`B*BUuuqT(?+-3>2_wTTG7vz%qJM=oDyEps1Z!WQUU;&vv z@$A#`9O8J;9Af+Dv)xG!xje@VE{>>Wvu$(8=V}uOpWVv-qB;J32V)pz*2ad<$svWS zjiBge11r(WAw32g!rAce?E9Q-GOb1*+*f{LBR#W;b+H~C7f4ugA)62-J;*=yoV{R` zO?nH2AnT=f1OY5xFoxaNo<*W|2w>wW2T5@<&E@Iwvx6-SD6-EY5|Qp z(@En}F}-e|NB>RINQJ8;pUMcp7<@Zw`&M z8LWvx8hPSw1_j$H*b&3iNZK}22|104y(uZ2@2)44drA9R7(kOtOI6M?N!y>r%v5! z#qeOm2sYX_g^Vt@gqGsn?Ctd_Wc*A^a6kQ&y-BnC08!m;Y!x$!dwlR;@5{cDfQ+S%x%w%ULkeN1S z@UE(ovGz7nM3IxU;wpGzRUGA+Q{ERvaOou0x5rF328xBnQraz zWX~KiyzIY>nV1|;PQIo0&1%beL*B-dqx8I`SWk=h^>93yl_CbyZ+wZTUOd_MKn$1O zE3%5i<4N>LF>IS|%4XEY5zph6aCNdRJ2^a#ymu18n@JvQ{-Zc@+{*$q7RRzvcgK;u zJM{WpH;?@|KaNCLn!%9TYW88zIO5UW6zT(8*waO^WKpy+SYK>ohf89~ol{2Oy1$X# zU>i$Jc!tnsS;}5mA4{CI3?Rw&3wvN@Ea}&-2g^G`*iovnovae8n-Cy?18j3(7d`r!CA znF$ycO&+uwK=!pt~v4l6q517=Okt9e_ z3`3@EWKOS-ByQ)#Fg&g|vt(u@F{RfFiZ9ReMyN!R-t-!<;LP=4|I7%IPp>b|ABmA@ zdPa~Vreff|`G=i#E`sbOmf*phV~3eVkRNR#IIR7Sg|QK2O%D-t%X-f~`xQ>Y+Rec+ zD~(l64kwEe&7h{aj4gN*PTpQMg+ZoG?6^bWWZ--gnC{TVk`>`(d$SQN7}mm$9u`hU zcp5^bWg~!#y&EKl3d2Y*3wqDfW3WU!FpRvW*MmQ;r}D~fgppUb z=y%`7U%b`p!^qW60rXvM$na){5nX#BR35y+oKOxU`iJ$v!q1IS%LpZxcj^OAHHJCt z5lRkTH2{khxy;maq2zR!AuKnkW*SUGiH?RbROtx9T3eO}~Z9O3q z7nsB3K1J-jnS|7Kn!>QQI(CFIAvS>~(3acEI;Dk>ZF`NuA-$Eo>>fhY#u`CLaUH91 zE`(HmH-G_+g=~ds2x)(>4{aBc*imCbNK1$wta|OwKBM%f@`Yg2_K+Qr#1g%!LReX~ zh0S@x5^pyF982uazB|a0c^d^_|Jg>eWf@Dt=pNh_Yp#E3>XA z{ds*uXrEKYEG`TtCbx~CS7jq(?H^3)GmN3;aT`;7Ets77+Z6V0Z((+<3no)`m_f8o zH8Xo=FzNoz98QhSWqv3H6Y|~yQqrQCfUiNs)n5b~PPs7?+=9rVOZ2|wtQ(By*&vcU zK@2|<445j@AY%Sh3>#+sYSCQ& z=NAE_{PhppNOSoXdY^Om(rC%>uYP0-{qB4E{&Mhf7e8V~?~Be)zQEHy>qj;^(VSvk zAEwaMj|7hsLW5)@<1(6N_v!R}#`XbY)#6KveDt8-Za*d@!Iw<)(}#T*X)gB0mn3Bv zz?gpvnU@EB$@l?AFyufTb8M+E*|dS)Q}S+Q@(1{mYtAMxL$Qq^)jmYK!4#^u*E1VF z_>hj7=J4QS5u<2!ruW1?4rUbny-9F{7Vdn zT}!j4&?#)Qk~cZ|(GqUWJI*G5@gj4&TS8*VD|WiG7uh>O1Z!pxR`ZM(c`(=lOas5L zfu>%Btu%x1L#3?!XfLwC*_7V@X=G!XJ&Dgc6WDmAjqMTdNfz}th6x@mtjB9lGB?Q( z7GzYjcMp1!B@YZh)=OV{L>~t9jb(rL_arr^^&&cLupA zOf#U@4nO8HqNT2+#X}4R2a|XQ`nwVvdJnB&qoa;Pg$o%PPp=JU9+4P@xsaSoVtBZ+ z2fOgT3z?=NhSJuxtj1Os^6yG|d@j7lzM1PnMw}PHASGY6pqmRRIBx;tM2W0Jfip>2 zYYrV|1#E|(Gub%O4D7$xvY#$Hla=Z8y!uQlJ7lFZnR440R*q|9>!&%BJIjo~xul*A zQgSAVDuz&MSIl~RaUz9T`YfP+)(N1Jipa2RIhO--*9m&vb0+996kEh4aI}7dRPI~D`G-y6Jtp;$Fh2Zgn6}_8P&hUX9G)xemlAnBIrk-^R?-b|Cf&rm(N3g{jTACrUyyFgjGj z)cV3jh_AJb%5X*Rvd+Y%~#FR;>VdQgQ3mQS~5 zrP*{+y9NAo31g+%v{N}fwi{${+4PP;Gq7zb=d$Vc{ia}_*2HDg@5YCxl46PHcb-xNYtH~MS< z&8FAZ2%z%C5-yuwc}W1uUrQv?Y3jDFl?s5=qDWz(U3=y`0=IA3zHiU!F9Z?n|#v z569)tm1fhs!o{$B?IVdaoAy2=2EDSOtTdbMRYR|9p6z6%+4SMLmcX2R!b-F0i7V-K zacCeb&8B;sTYz9$3M3Pg^YA&0 zG@G8aR|s#*&oR<$djBkXOt5>$NVDnqq5AM@)&F|z2TwPEy^GShY`XtOL%7W^=d$TK z2O~(dZsM}(y|u&`n^ns=jc(aAerdOpH1MhYlmrZ+LF@no}ja)XZ zw!{#8QcAgO+NO^I?BadpvgtS#eF*$SxNLgxa6Q=R_?pY6zpfQRMdJxBoAyi;z~8T? zaoO~_0|I!|%u1x$^bLA!Uw3R~ur!-Kx=8>%#^2&ev*|6K0R|BSxA{&k5IqtknUGG@CYz)`tZnk{M|>tzKgQ-rI_}Z2I9;BiJ&jp39~+ zjv7OsnpQ5Go*HTb&e5%0Hho&d3~u}Uug8Az3Uh#0gD+xHxZ2;J z%ckx1Ea8{sLoS>C`P&kL&u-?j>3gTeuy9#FE}L$OruPkeukfVV^j3O)W$=1;ur!;l z^cBO0E#VSrHmxHP!`+#)SZOx>;R8K4);+^Yv+0MOBFO9WmX&7H69ofvy{T42p)(SR+jGt9p zHhu4`0T@N)aM|?r&HB)DZ8VonZ`!K|^Qv6AY})L#5Ik+JbJ=vkF9D1f>2uli_M7zk zcW|pjnoSqc>(g_e$4I2vbOimp)nqhJnoXgEptcY`Eq}jCDCi;xWf@nsXP0u`I0DC-hxNQ1%pdmz5R&m*M_YNb-U)sWD z({9U6s8Ji2O)t4)3Kc_|xNQ2)7c=;Nw~WiC*Q?U|Li%Z3Hm%TK1a{-!bJ_H>4*Hyx z&RZ^pN$-Y}&;_3_EZAugCrsHBuNC!INgwtEk%U_-`2N;PtzZ=(rmhMKfNd1?8i#8>B7AhAZh-{O0#JX zfjRK67joJ3Z%s4k>rlsK)81hwa5%h`%cgG}Glu;7RxX?FH{A%1%&F(H=|i;!kbI(u z%cdX3=)(mjnaie)BlIBlQ~;Mv`o$%p_yDZ`;OY z(-s3vVd(u9E}NdW-V8dQS995P>=Sd~h2(PC^!Y#wxcfYY%cgxjM6hM6JC{v6p0R|~ zB{#Wj`t%rjPj9j@mrZ*;qINo+JZUzqNROEw%)dNoHl0C_rAk%3CDLqqGd;$3n*-_C}9b!Ai5~f%h!ooZbI=?Ej7ufu4a2E6t`Sf3kp^?UAfBn^p@phnfD_Ts9qj z&J2>4RdLz056=`Hv^8_tbWNQxw7Rr$+4LbN`i#WcCN7)4vB?lV8kKX|^nn=$ptCBS z%ch%$>4V$xP%fL^Gn?kWG4Hr+x|4oqmG?Q%Wz#YAyX@-8Ib1f~?U(>wStLlL*|ZJ) z?u)H^8Z6DG73g=O_o0(KX*O*}zbpF}_GF~lva7e)mXY=$F>QWz$nL3;}d%xNQ2tO9Pnbk;i4zGtSU^ z>}j!FHr;SZ4^*-}xNQ1wUm2@+4PBhrm*N+ z6PHal`kTQP^$ISVHZC)VA6qiGZ2HY_3-}Nl#%0rk%ISRub9*kEzUO5L4LKLMY+9dQ z3#{47aM^Ucn;7Pt|ICwS)BWkSL&Z~8N19Dr(QArFYP%%TZ2Bv`*4UZdjg@B8N%R^- z@NP9L&8C;Ew*LvN$7pNC4Y0-bjWrA_*uM`NVDla^!Qok zGj^^tn_jSsp0^~q@TA%F(=hs+s^vI_%cc$J-y=H2NVDk~8hQ|8`ht;W(`6NUutb5S z*R2J_p;;fCYH3DEv*~4{=<#z}371Wu+F}GR<7q}ov*{V0#*n;=FtE7H!hoYeQp66-Q&4z`sX7N^fUD0vgtRwEJ5UTo6DwW^%uj+ zL`yE4PP7%nX@7Mtn`S@Kd$8RtdD3jUlU|=%tt<|fX49jb=<__)xe{qMJz^n!=4$-{ zR+>#S_LgvS%Esj`4M`@>mjHvRakIVkyOa@n-|8#9Qks^GHe zYpdw-(~M@3G@IVl%LLxg?z`tSn_d`8uN|0XE}LHPf7rXrx2m@8Z{Tz)Hg+64j$Q19 zopi&tMXY0YH^%^#qu7cK2+|?37jq!eEz&J5-K7%GTtjD@kR~k6 z5;9yiy(L%^tft&&xNQ30hqNY^e%I!*={@(f;n}WOhRdc4y>wtv?sq<$4zJdQ!@p|z zYk^;(}~MX zA>oaP&!#2En?e0|J3gCUlxGIF4UhBL^!k73{d4IgKAX-V)X~~Wz-7~G=>5~%Cuk9u zO=ktuJmtkZ5tmJC9i)43>v;M*$sogv&0x~UBP^FqpP6O`i~L@&TsHky!xTK;2eMo? zownQr`X+y4xorCFVEPWkyp+$Tr==LeR+C0Po4#aC?=7q8XCKX`*RIqDAH6m{n?BL5 z3(dRg_-r~aNC(=l7x3A%+H?Bsw>pl`rc>;+ATG#@&!)FVXo9`DEuT%F8Kw#Mo^0Z? z=~=HeARUzXZ2H({4H$S~kBG~rPtsbQ$&O)aTsD34q6QR%r3tufI=VmuI?t&yTsA%L zye2ek`j_FdX=bGs+zfGGxNLgaENy6-_=VxJ>He!}cH@!BXVYP)X^ouVe|_vNh#us( zH}l!FhpYh%^P%r%X*TVwX9({1Tlj2x>SJ2-d7z5VrfXx3LH@!7QP zOkL3UQpRV~_1)Ug7L>wg(+N#lu;(|+XVZcGv|!r#S9~_T*+>)Qex2g8X+QeDu5!UN zKASe9@9~y{r-;j@XVCkn(l@UFE}PDvb^iXlo(s5a`h}kc=nC7Phuet_Y! z={HT9aA?SLhRdd(C)5A#ssM(|rVnOmL%vrM!)4R6q;(<4ri9O?b64wuLskQyO`oyR z2lw&qd^T;LW&m5RxAEDu*BB$%+g!(I(}FF=5VOCK&!$gYHG!Oy|LbF4e#I2JrugvL z^z030P^I#a&!%_F)68+pHa?r)MBlrPi0H>>)1|b|U$OkOfXk-s=;z?opYH>?Y}%OC z`4>J-5OLXbst&C~wq49}*>oj+-|P6`8p~zVmG!0&ve2I8vgvGDQ}9av%yQXuPNOmG zcgWzg>AfLFU|?CnXVbz9hT!p{na`$6<{E&ZTRWdkt5)cNdr=FYO^5z+BFh0SJ;j(GVliD!8DT?8;X`cr=@SrP?&!(;8bs;ILhR>#N57vjFA6ofrx^s&G z?6Yd;vuW24hEQ;)iO;5oR?>gZRzLV`ddP4S&`wF^v+40uXl;NA;j`({ea&FhfH!t{mF2Q&yZQ9_ z%Dr~lCd^UZ3iYBOzvEZ}mGMZb>j2*;h(>65Ea&!4t z#AVZ?xp!znOEoT=ens=IgnbbLE}It8TrAIFKEq|x@Q)@~+`GbX*|hr%EqLMdj^VQD z#KGEd=0-5XWz)@*=;!j2bcV~O#|m}fd1N`CO+T~K11Ys;KAWCast@blxAWO_(o92G zG^dr%rsth9g7v}Gd^Wwxo#tHoa`|l9DcS@=$|Cq|dH|Th0&^EWn?7`h)_9a!^V#%I zTIU~Jp~+{{Cusf{HKJL-Wz)6ELa2%yBjB=W6?(mN>ogIUO@}=f!ugFqMO-#*HBAT> zyLDJDn?7{I3=CxMuv|8s?q>?kCa$aj&8EkMn807z*+5IbTnpG{w*Ida6f5D}M6$J6`gg~yu$ zxoo)J%#4c+jgijTsD2-Z~7T(wTt1h>0{qDK^Xs-;j(F#r8QmWJ~3Q2 zeFx}$U}qx3Wz&WwI?y+_h|i`?Cg?$Qdj0>h>4W;vFQtvorc*u{z_Fq>KAT?JWeAP3 z4SY8J-%?{3F};}2rt^21z?y_aKAYbCk115Nf8w)g(=}$W-r@R{$a|o0ixpgyVj*SuUHN7)9TQ zH(y}6Y+6gs3`VHFWw~s6@K{q2&IOjsrW5;_fai@gmdmD_z8k?~xpF?69`Vu;a*~?( zZ2FXu0W>~r=dt3-1}vI6Tf}A4b@X1E)izAP zWz&af9f*dYLBM6xwY1KE-dzob%ckEx(}WQk)(n?T>+YfNv9mrhTsAGSNgF<$j9|EI zI_4yOzUrULXVWL#bm7jw)qFPX)kN!6hP3k8^zJ1FVDzD#&!($y7{bNP&3ra(7i$DB z6)X5`dP#>dWVNRA*|d_1Dd=Djc-KXU6pmdmCsrReiaj5*6?)5(Tr zFml2pmdmEMoi&Bz0lqAkO+Ptf0<+Z;ST391Xk-kX9ff>0Ef{PB&U*EHHmwv#-|ITG z@!52-r9KoZwe#8ZMu8s4TQ%_6^qikMU_;Nza@n*+k~TdH_La}3Gh?;DdaFO5P4};% zHTm+-_-wlWV*1|l;XXc_p5a4X5=QcU>=*B%InmHZA}*UYpnGuRE-5uGn_hE7gPy7M z6L8t|k!TI53!TAm*>tc_6J$-!GF&!&K~)PhuDxcsY&zz*7HrH8Vz_L2nxYN_9ZhAp zY}$P>ty5j~gU_aO&g+3-cN3pY+l1?b;k9-?n{Mqx-@QO9pG~Wp8o{CN8a|uWxn~U9 zO!E0`da#EHlv_me+4TJnrtrkjozJGd&zga7qYa-;E6_T(bB_)AY`Wp05Ma6#pG_+y z(d_c^asii3KTZ{b{$m9Zmra+@Iywo}3K5r0k6kQ;C7x?oE}PDKY6g9+Z?Rl9Juco9 z`fqY(xorAywh53q;VhR;TYNEw)q`{RY&z#QttrZ`;#7|6`YuL|iuANn=E^H+@<%V*Q~L+Eph?n?oeO)sS1 z0cFB11GsEjme%BE1Uz{m~sY%k5GwY!agJy*tO(@De-Mz+xJfHa#<`C$O|8uS^4X4C)oOtjop zGbsA@kUt;2Y#psLS-F?LPA;VP_BrGDYjgb#P&Cq+KkME9?gn@={C)s;?pyNN1~{Yn zoIe}B{p1G7x;mQSe!gM+1`y3X$X{=^7sA2gcKmhsFEh{|AIx7@&NPGBFZ1~8kQJs- zXZ(}Do~}mEESM{(bAM0CFk{FM9l&3U==)4}uVMW4N?HT(Y}_dRnmZeQaKf1XdmZHZ z)sgE(0F&}Y28rw)xtJ=^rzf$K#8U2k`?`S%^To)T~(wOKUO!h!2W07pih4s=@R!1W@4(g1(K zBqax~7XdUpU(00X*mJ!IV6ygO=DnLe*HZ%2Dnpsqm+iS;1du0H$?P(==Xw#qojtPZ zHzwP2y$GPb-$3;TZST2W1Q2IBLj860d#)D&sLmg)uIKum>$kwK_h-M4Tu%vZjp_;| z&RkCkZjI_^{hYbpAlw?&b#FRzJtep`GH*9Hb3G-vH8OW+I&(cGxHU4XB%HaP65JY@ znctkao)X*|1-sunalJvfHLA6qa^iYQaBCEu)NWb3Oxa6Kis zHL^9qAGqEi+!|S*hab4!Alw>*Quln|dP;C>3@Tjwf$J&3tud%t;RDxGf?H$It174FflH6i#$Q$EX%pbhL|fMaQ~luIQL^$Q2#$uW&`jivwKI@l%ltIfImFQ8M)-I*xbxh>mm4endxg&5!6w%fKE3aWj*h!L(Q(Kk zPjsx5^F+sGSsv&(-NOSNzhCu0$5=xTbd;XpfsPMb-O+JCoI5&(zjQ~({|>pM+Xe)nOD5f@wJH;I)0wwg^mgB zp6Hkv00{I$o6YL&txTKcVAW zds;KuvmfW2`Gk(1+Mm#I$LLS!IHT4V9jAo&qGQb?UvyOY#}^$(34GCUijprnW>ow1 zt}*CeLlHXKP7&pyT;j0qA&IA^;tir1_)cR%d^7+<(p=9ZzfdqvPb6{=I8d|7J_jv0yhrM}x%# z9VaOebUd3KgpRvBgV1q=We_^b8V8}{Qu^Jn*D;}uMMs@@79G1^vFI3mm_^6%6)Za5 z9zwq}_S{!p%SGrY5{b|;{I&=kPaP8Vt}$p_@@I6M{oyk@zCQCA9ZzU{M#rcTpV85` zE*KsE2@OU^lZV0Rcz0JYI*w8cMn}6o!RV-)59m156VP$cH9*HK+DfDM^YPbIKu7ss z1RV#(5p)c5C%tP_KQb^39WRxIqGL@!C_08((enj8pO31WL(x%kPAEDCNQI)~`;;%} znC-z%OEMfCPp8xOY(398Pd|pCqvQE7bo9~=L&qJn!qBnL z!x(fNu{Q=CZ>zD4I@10o=qPv- zg^tokqtLN?WfVF_s79eBX`H4qfiisj%j`4(9!C9EIJx_#iFC0Wh^=l62_wA z!s)T-xaxNdI_k#9pktRuOz#@iKMqPl$G{(7(Q&HiD>`;qe?>=wEnm@b$=t8#*dYBC z9rIEX(Q(L!M09jKmxzuN^%BuBV{9TizO7F{$Cos-=zU(bc$$EY|L#vfM_cs-bbQ$- z0UdSg_3mXEHi!$0noWo0rMxc;{F$I<8ogjE*ygB%|Z5GJ3YL z=X*!9h-Obc-#d=~_YEBy{HrPj9cPggbQIX6pkw8cl-@N4Jx z3mwa~ve0qK=qz-c+L(!sdEuGp81pz29VPc>qN6R7iH`mIWujwfK?XYB_0B*?tA8`l zQEx*AIv%0X+_`(tByE;?GUx#+m~PA)p$*_w-v zXXfRiU=(xGM03G*10Xm+fwKToYITMc+^sX@|DXk10^FNlM zquzxwbeur@b@aZ^IWwjV9d|aBqT{g0QgoDlT8fV9|CFL*ym~1*YV|Kg$IikMbd2&T zLC3J`CFp3qk@n^2dCqb9y96BrI*ZXUEU_3JPk0yiu2FrAY9%_(tgJxCS3wo%c>Hb! zI!0`(Ku7QS73jEEt^ys6GRo2MwsSc;j<{Hkj?WFs(NSl7IXVt$`hkuEB7UG_#`7QO z*naQ_I?65kfsO3J^~5?_sugWpu6qr}N- zbo5(SjgIezR-_4v(9m$h=bd23!kB-cedUWj9w;mmLey>AEJ=*)I_r09VtvYn96Vl#CJ@4hF zOshl3z>ZpUT=cCL9V_0~qNDGLT6FYWOM4>qyq7yQq81&W)YPD(eQ*srdfux+$L+^! zde<1Fl+lEa!(E%u(fVQ&I&RZ#LPzhhP3ZWlxe*(SA}r@nWM>Kli)q2u1FR&>lD zt?1}x(~6D~=B?;hy`U8x-^sV4qfKTDI!1hKK}XX|E$EnP*n*BXC$ylWL31-Y>O?l9 z<3PJ+bew;<868(FZ$?L*{>|vv(a6sW|NwvSwG5_-~bga1l z3mspa_|?0{pz#MKxLK2Y-Z9-wf}0u2=N(1MB)FNOeBPlmMS`0d%I6)Y`%7@MU-`Tv zv!xpyZKAu;@$B<%boAcejgBjqb))0wf!*kMyrc^qm-uy|quQ-5bnM#Pg^puqccJ6o z5?$!1_N@~g%Y8e0*Ql=5M~a)_%jX@2t&-dfUq0_p{4NQ-dB=$;Np5B+pLe|SlH_KF z@_EM~J4tS4D4%y6zAg#9c}K}XNp5B+pLbj}mE>l>@_B~_J@?e>c#EEU>diaM2TF1? zeEGa1;+F(B!s9-;c-Kq|x#06KQmub43~*?esB}4Wyz*HN9V?vV&~cEh z96DNGkVD6kU2^ESNmmXXTNlcqWAIoxbnK*ONP8XA=^4^qM|FCJwAWEU&ye;yzVwhq z$C=M$(b4y+EIJDI(OJnoj<%a*(ecM!1$3-Et$>anwkx3H01X9nWacWMqt{3UbX1mA zK*wt}^5{4^T^=1vKg*-zL>GBKl`Ep7#WzKC%nVXQ$9ay5=;&;th>mMcE23i` zb47I2(NaXmN%Ixa@%BhXbhMIDM8~RH1$4ZSseq1BUlh>M>LdL<_c#{3;OB;OYgFgv z*Z1C6mj)=KW6K+5blh&GjE>gFl+m$!vobnvTC0qXUuP<#<3UwrbX*{zjE*NNmC#Wq zMF|~gFE(`abWlRaf%lZq(f+IwI!@c6gpQt?bOwEoqrAEj|8LdJ@E3Cz6k#{5xlL?t zXYR%*!m~qy3P9|LzsiV6yb0l zJ+DVTFi+%^;5V(?EV8#|-VIcOHT2xjoem@BzcET6F+~I7`l&GH)0Lnke?4fn+!2gi zqy&z^>*3#H#{)uFDnWbHdT_F`6K&E}f|%dyVYrnlTe3k3xHCsGSzFj0yXfDUr2((P z?y=vFC_&9dO*riB!7jX@1o_LgK!3=s%bE}?0kp6ci7+XdA>8VHsO{PYNXfMRXwM}eYvl3L6n}XxPeAcy_{{CrQ zU*F0IcC(T)gwh^*2}4|1$sx+He)a}%GrYsvja3FS-wjZvXTnaOt_<-*HbSVgIp>aJ}~YVk=E$(D`R0%!{=Xd^c8xH-e3Dt6G(rv`rZle{29_ z$!*NGf0QBo_y*7%V$0k=t_*<^GfOtj>_PC))+J{4OCC?RE9))&JnH-Q%@EtL&Xw9P&+V6 z-7!oV{_nhiA*BZJ=6f3>>8A+x7imAq<3AZA(Vsa2f944MnIrILj=-Ne0)OTR{Fx*0 zXO6(1IRby?2>h8N@Mn&|pE&}5<_P?mBk*UAz@Iq+f944MnIrILj=-Ne0)OTR{Fx*0 zXO6(1IRby?2>h8N@Mn&|pE&}5<_P@%%@OFWoBDgVxK3lfzPL`KYO%OZ!*rauPUDKA zxK5*`NeSyT4Dyt)P9rix3F|a0Je06bWBM~Ctkc+MDX!C4eL!5N;bbhX({NlOuG3JM zBCgYT-d|j&G47`#)@eA>T8rK~jjm+H-kPEy*$73fx9Q`li1jw%PsQ~%v#yHkZ8q!^ z*V`l-i|cKsEfv?>yq+Ykw_#Mo^)}M&3RrKmsz?FrZAQi^V7<*%Uj?kUx%^TA>um~e zitBBT9~IZzv~LjC+gx5LuD3~_C$6{2n<%cEDp3*FO}%WB$9fz20(q>rnHwXI^)^nv z^5`h}N**20+z{7I4LU5Yo5~T2>!wDo64y;NPZ!rsZ5$-7n-X@&VZ9AoCWrMlT1j+H zK~LX?Z-H{?D11lj(|YP{JRgYbru?sq>)+t8xc=>wP+b33uv}dKrZ`Pp|8`}Nxc)7> zLl*0%3`%9OZmK##7VD-y1<0af(>pp7p{I^9;kLN`ZSDzi{oCv<;`+A->%{eM6XuBP z-&}@?>)&QeitFF38fAL_t*YNEk-@sDCy6pxH>DRKgN}i3WYDq5N?gad;e@!3(RYiu zj&bT*aUEm$OmQ8f%}{Y2W4xrej?uAF8tbN%QlznNN`XkDjT*qj6R$RxZ zutQwOXl^8~W8Aw&T#tHWmbe~u@=$R-s%^Iv*1rXnOJV)n+!QISf4f7Z&{5J+3LRhB zi0e^zpApxiI?|a4y^fc)#Pz7f^ThS2g(JoFsB7fJ^{AxvcUi|dMajS|-tXUmA|ici-_;C*#j zh6LVMFMW}~`ZuAA1Ud#i5Z4upE{N-jN9_^U6}#(;>xvhsiR+3*%&*%c4M8tmwPwX`Cq@>jdlK+2HjZaA3jN3AAYXA3+uyo$8=$R_^TIPSRX#~a2M8x zyRGWN`ta?8#r5G+OFOYXd}2T+)`wT#>BRbQ><(?aNZik|!GP5Ym{ zYYcjH>nEPqc)$54Iu4vEKCkhkvmG7PliJa7ieo$0`RAT#N5^Q5c65{&AwI8hzorcx z`-Qfl~k~O3%gg?8n7BTYJ~2zIJ^p zI+~0WpSuaKZb8TA(1MQD_ge70M&_;-bhKIAf{y1D#OH3jvzpOyrF%1;*9f`RjOR5@ z7&oKil8NGTH)^d-=-3t8gpOlhH{p4WnMaz?QEf#NI#!GqpSx+36Q7@w&1po(Q*Mp8 zAGIzuqT?%lIv=6uyoNQMmC#$~znsoW=&kdg9^HVB7S9`SKQp3k72WilT94z4qB?YRj;upR{}*+*A15EIL&x7s z>d;ZYpZFY{dPyxh*8A6@WA3e5+>e7d)}o`s-{Ny{6C}mw;L?(7(D99Z4em#~Q#I(g zL#qZIEk}#b!QHE^Mn}8P^t@rue$;+n-Mhx1jW?@tKmN0+8XYrdh|e>+cT}OH#Mdfx zthTR0$M>hJ(9vdn6*@)?6Q5@^t*%7J)R0Pay!D_G_oKniN_5m&Sc#4UmBi;6=jTbg}=(*7z$IcxUy=zogURQyR!$*kErCL{&qvJM0XCm~RyYcz29QWhvo#p6g zyr>)7|P=bz&SCpV*#Q^d7V&9@-boBgGjE<+Qi*Y|b*;0&-_A|xji#@yOIqn|E?S)0? zcqpO>9WOpF!u?pizX%<_s28E*U={H>af#wWboBQtM8|hG3voYY2@BD2{|xat@$&8h zbhP_cfR4M~7vO$0KUsi|lQj#_as4RqIdRjP@91bAOwZ%@?8gD`zW1&%XzY#exF2V3 z{Em*Vri;(}AOD??j*$uZ=;-r4ANS+lQ~BsM#C;p|D|66s zLQoDmp0UZn{kYR22OWnk%t1#PIdR{HB^lZ181Ise`%(K!Had11WTRu$U*f(EVNF@+ zXdRt}jxKgtxE})#W}#!)(kyg5IZoWS;hK!N|Hl2yOmviR$;ADbc0Lmwr|M>+nUf!R9jvdP~(9yHMxc|o4!gO>z<(rOaJ87Sj9>+-qY3MjVJPjRJK1;*>=)Eru9d9ye=$PF{+(#v{Fclpyd`d;fJvUNu zKfWaXbNFjU;vXmCX$I#!4h(Q(P$MBI;4cO;@?{`^FAjFA!dHIhtEK*t9k6L3HF zznp-MVfqQ^XfsaS*T}jt9v$_f;?eQwi+J3Rmkz|Eqt%jlbQFvg_cdBCE$&Zcnh}SN z5zcYAA77k{L&sX}ICRV&C+<&muPGKCFNDXUqwnKb+>fjG#iC>A(pYpn*-zY`YFR-H zIx;>n=qPb32KVD%n_|#$)(mlfDyD<>0qb$B%#TLL_Rwf_lz$qH`|->_(deinh(^aZ z%Hlp_cM77=afNRbI{tk<3isnK(hLjzyxQ_qs@Q zOdc-oGgeR;fsR!{w4Yngeth{lqIZo!E|w9v9|O%I&~fTialg3E_HcAGhzm!@C2zxV zKQPCbIO=W-?Omh#=2fBSxKCBw_b=dq_e9=))*B2d!juH389aQgwj#=S8 z==kfY5AH{WeLmBBV-souX!5jDEq%+>=cuvzB9e0lr_ctEV z;DwH|poSkt$PB};Wy7xF{Zg%cnqk7qL zXLM{HB<>r(tJDb{1^!OxXk+Ds`|;dXCv==O#|a&WON#r(8zp~0$0ElMxF5~We?Z4U zIv>z6ZjepwhKt!AMAd(#!WSZLzgzYRlz1Wpdb>|bpVtnCw&bH#z^>uSM4Gl?MejSgf1qY0Pj{E^EG9EdgTc`~6Z zl-=Lofz(`G5BJSqv5PA0$-JU&!g`1-)nvJ!=bY34x%^xFb^Iz# z7`@l&f7f&l`?ly%{(9*OZ5Xp8i@&bhtpokWR`S=IUg^T8aV`Ayo^(0~r0yqw&DAQn z&>4~3-@kR683c9PGB3RpVQe2E9QwVPDSEC5yXcJ3yG&mu%2E-g)7hhDw+{-|A5?^? zbQarQ`)Pb1CTuWNvGTA65PjyxQpGh}D>l@YCv zkO!cB9!`&2Bbe(Y4=*0k{!5zDOxkmKSVd>iR@oadpDpEKrMD)yB-=362jrpbUoG$t zbZ7LX*fj6MuYYGt0$9A9g% z0qnWZ&K&w72VGu<;JB`dx%o{Fem5DxBIO^aM@f4(Js@OYArb^4y3)6!h8g(3*=xhonvw` zreN`jF|KQ$ zc$v!5-={t(J#AyJu8@USDs(34)Oz;s>GbDGI$#}K$PODM3w5sA;7}6JuIP|~KvyjY za`$1MmB~OvvL=+cJ!DsYqj^1@#T@y0JNtl@fk+1pkX<=|J#8-o^XTm6^KBPJ<#%P^ zJe^0gwDyTw;29YpXK3G#hp~d39WtdedjdSwRLy%+`U!D>E2jqco`Q(1m+TE0{Go(opZH2l1zynf>9?aJWt% zMty8&z(X2lsTo2-cMG%sxisipF#>JVY9`oH8l3!%;YeH#^X`B&v?iIr_K^|H08?og z5pD_(j(lYDmebk*Tk05Z#mG*VhBb7icE$Pi%4V^2J1eCi1ztDx;D&D#JG)U5Y@7FGl%l5mI4f!cO< zZlE0P>ve|CSnoIGKS2=f>$S^+&IK+X#;6XG1dF+vu%dVm^Yga^gqLc<(2OUHMX3ZV z3e|$_&3??(Bni-s)Q06_zcQOx36QVV0k1v9%rScjcsx@Nc1>?!cHNZ#g){mvsJ4xn zeOdx$ex`G;BHNhJJ0#$ef)U*Fu4l5eBw*EgV}RF1O!R!(pY4zd=nY6@evFcUyd$P? zOZ5{oLtX+Lw9MeQ*<&WUnD$%iFoVD=JDGp|X-0oZ2rJeOVKl91ueL}b?D4rN7_zyW z?56X)blw~cd@-k+RQU+u%dSw7ylgj7GZljE+<7dM(M7&|F@uBZm)Wr&yU62iQ^+6m zj&;4*MWzik1tW!E*4n6xe3CN(n|bN1!sIR@lWqj7u9mYEZJi{-))3AQY-T6Kc9Op} z4B+CccJ}S-PV%5z54^Nn*%2o@iBh00Wd5pVbJo$HU(o@*h+OvFuugJ&r#AH88p-ad z>L3<}wO~oL3tJM>L5$vLf`|2OcFW@qQuv$B`8CyMAMWiSd+*XYl_T0jrvx3O*hB-a zrc4z5?9)NQ==E-c34)BG-$a)FnSVC53by&v-g@+ZyX}`2v(oA}IsKZ>1v9_RoS}LB z#zR`LKE{Qqn)RC)StFpOFS<-2UF{t+>BLXc7Gegc?_Xvw2%R;a!8_eF`+fFr0J+BY;Eyn&lb|m{jdp$S`t_p|2E>TVGK)e7qP3Y+DM0@5e#;$XUA`9BVHi} za5A)weKNC++&QZc1r2TN3F$U6WVRlhTGYTQWweqLbvp3%d@7JUfemLtK(?UGyUaKwt zPqg`E3$dhoaPpZMYN5wk$RfHoXD?s{!gVcVJl(ThD`qh-hqVwDx|jF7KF^%3Y$kt= z)`AJw-Y_N5Ozfq#;V)mpggk5}iw4qOb7RvO^S#aF(MmdxJNO5qC1@tIZs>vQ$0p{a zax=+F)Q5*Q?M&?VCSo$w5Jo+0Ww!g#T%Pv%>9(t31XfKX`k65Zg7O%NO-37XuQm!Gl)+9?t|u*{ zX&=aQpV@2qb>z@|EvSro&u*suX1nQUR>h!eY#*yS5=B4DZe3W!{@z$e`kd8(*CuhI z(SO$wYx>z2UH?4LT%wLh(9cA#6Bh&$>9xd&epad$^=HbRYl#f~43*!zo$)+hOLD(y z!tomq83Wx~;^3kMW_Nv<*W+u6tBW>#j*e%H+iHl(R~>NvSjafW)Q~ZK^}t|cJ#*2n zhA?LOaOgoBlXSR-?0RhgpN6$FAJ^27b~^v7#J_>D7*<0LO*ICQQ3+#QSxur1O<=Kk z5_6nXlfD~F;dp^R<9ffETwi1cU*A1r4EIzMvl=syY244O5LA=-^qJ(pb)y-1Rdp zo>4{o2b;n0s#omT?n*LpjwuY=9K^P!R+1wVOyI3zDjVorNe;CbL2P>&>vq19T&2CX zESAt|5IU74?jHl#bgrFk9al*Xj?;%B>8~^~f zGUu{3WTZ#4Er%*d<8>{N$#G}ruC5?|`Dj9)-!|;8p%tWxK12TMG-6FF%ZW7YOZN9i zX?7aT<+3PDava z+Wo~hnUQ%v=&V>R_!j5Htn~gthG=NRp};Vv@#YV5-dqQi{j-_cjX%hvC-nK#u8Ikm z@q;YP(}QnLEzJ6^GBRN@ojLB+&YVjrBj=A8!piT>jIJ~7-Tlc3cF9*V?&r&hemR}D zyDO8qN_%&|?J$8a(IE_sEhED#OyP~O19QKHX6~M5(3oq@wG_e8L#0HOes`#R&Z^n0EF~N0cZw%+2SlremXb93U1NVvA9ihJ2}z{iK{VcP zX8Vy6vUj`d_c(7hbY}@MyKMrSpT)6n)k?^Uy~fZUUckyKmyq4l zjbNxv9h;t8Oe_lxpmS>*+t;g@=snkmsp{=)?u}ydL0=ED=QXmTjm2b-iY}a-T*~^* zC?-#fwPB~_H#VZPhzN7E;OxpkHtSmvk@>9&=U2U8A37D0&Xt<*x5Huf)%hZFU8Dhf zR{zEB)hQxDdo{q<hK*$lCGr{yD3R zQ6UB7;x0XS72C*+pgq{ z235Q7%;((i#Kq18GF4)k<(}WkuP3H3MAwrszW$xOJzxf=p7)q_G>f07Duj*kW{m%g z?p^&y{(cM^h4O`d4y`Ft{Vg%B=m zU(W8)$tR418QdLrgFP}PpUllMh2r%e*rSbkWKp#VEIJy>&X3L`Pt%M+>Qff0ZI?&f z-Wox8btOCWP#&?`MDL$QEv)VGJaS-w0lcN(Rqf~;gcZ^By93k0KCj3n%Pn=mDX5ZF zA-Tjwm(EQ-kj3WME7gFn z+RNDB+#E9PiU!!Y=7_>Qa>zhK4M^3_2_%*|WY{M9obzInz;Z(lNuV`d?~@gn_cLC7fuf;GWv%6+EfYc~1!p%&!$crwKf*<{Z>ZFsgTmZ?6MO$xnqU{UUO zW{*xb38y_*5C5uV=8efFyB6xhxJhk{c0(3%zGMI^HnuY=QCVbjlpzRR8W|Ou#cxwI zhTkov%+NzwaZ#7K8<9#5zNti*>mYYD|+;b^clu6Ozp#uRC4p81{8#)2?B#s zNpyh*be>aZqHR*iyz`pSu<2hWe0wTkR%*e`5C`V{{8X}RmNqm^{K6blOeOtS>%bU~ zOvWiUg@m2f1wTP0bH*cuSP(tPZ*OMuuBH$VSpyj6)6Njn6ymH$XJ6iLVM?Z_kg1Q2 z;QoOs=5S{+sf{%T`6JoP;;+dhqsRm*wuUk4?~}=j6nalHcVZgOB$L2bW>CB5Cev3Z zne0{|L6_OR@UUeY~Ars*pr1?3q$@IUwDuA(imOu_>X+yqO z5)*JRfy|QDg&>;}=G(FalDk?D9I_gii2e!WjEz3Hk8fwJO5%xqngMLN-o|WaJZg4Q5cK@{q~N zi6gt^>AdDG+nCcHab(kV`rH!Hk6C&(j+Dj-L9zU_V5V^#v7?`ZSAV__Oqm)-j6H-< z_%uP(r!$tM>Ih+o?P7M?*H}{NX9kWBuCXKE(d&9s2w7;)rk#u>*|MhKmHwIa(26BF zjmEIwA%m416HE4n7=eLh1)EtHLxdL$!Q(|UJ0moPl*}~%L$`Le;0evvX>V2cq84`M z!5A{`y)KLzTFoXbiy?Cl=)kJOIqc*9G32Hponvkv&R!~xCS$j2!HObhc8n;R_&m^r z*eO=5xlJ^A(5L|;Ro1bV+oMV9O%1SZuM!=b8%-wD8QexYRYc=uqY0Q%#|VL-Gdqf; z+0yTcK@!Xck0=r?qY2)O0W;@n6j|@82_NWN#>+-gB;=wNj8AZ5rcH?=mM67gd{Y#2 zr6ZF5cXi-FR~|EoX71MUx{wrA!&JYGB)13a!_W_{OyY@1(z(R|_F1(v`!pko>jy(9 zxYNY=jgBNkE9t*ys~=2uT?832+yt~!QkkeP5oG)nQ&?<5n4^y)$mqUiFlxXXM*Bbn zc@b|0RF<8*r!1PA zZ#IGPcfYcV9%008K7GFOFJ|Xm4I|KG2*)=yu%nH_$TAlL=+{YS0Z$4e!)R~V7k+K* zi{GInbC@3Ny;9H0ehnpivvuH_P7z!9Hk7>nqz%#U6WGZoLdj@fEeNpnWy$(bBAulP zlh{Y>gwdhoI_-v%ctNTLAoaj5x*g>q_moLO-y9T(q{3|;8=nEOmy+adPs&()C zLSCKHfP{S!f^Eyb5MinYDmaGCz}~ znTD`vPAhZL{WF<&$_Um6S2HuOekQBjjp5P0T&B_RGjWQhGo8yKm@gA)whpGSz}$t= z{1r?N-7$moQftO1F_`?EDTLq(O{Vy5Fgfv32vH-N1u@5iNo}$asv^e-Hm(aMD)f5k z)@h7;b0M7H_*3Ll2gGU`?N7T~hkft`$e|l%U?6jcO?(I>-Om)7OAw)5cz1|;4)_x->oKnMT6%n#|j10u$Sh{n^ImGSicdExPQOd@Q%PQEr7VwJ-FlY>cFY4 z0rY!{5OM_|^0*Q}BsL1+xZiBH+Ax4jqIIWric`j%bY=1&HXH3i{Z zVE;<+CyD(`!1G2L`{}JeY5HyikLAi)yW{?3#7jfSNorza*Z7lDMh4LMu$`Sf+@I7b z>cjeTtt?yXN2Z7Bg368>_RbeSB4w=uE#`Tw;X^-Cen1sr?kL1+m$`8 z?nf3nYJ%dsJFHZHnzKu2g6$Vwc5Tro(vN0IDS{5s_)nimq^SlhnmJo!dy8i4^j@0P zHcW7M>nC!^S_3o$4FV;at=G0{z`VN}OcTx4-#*iX5gOLam^5FayNABV&icrl`{+v~ zHfh7BlM#&a6<-o_l0IMc&t-}XeaQ(oUAXgaHS=+TFY#*9gXKe7nGLNzWcLySF#6EW z1jYG~>Kle|adR_c_ST2k#Tvm&#R}%tahk1n7(-TTI&*f74^dJv1)a`dreLTK$!Rl% zK?~nAq{f@v3NnMY`>!(QbpG!*13F7xaUrAq(3{-!62c&ZXu*ly-b9+(T`RLu3m15k z+tEUJ_~oi-OFwTi`x<@svUMQK6nPO#Df&DUW6nx`@*>HGW-xNXBi7}n7uj~!6p{z{ zva(ye$dfZBFk3Bwb(!NuHX0d2XGbC1BIQK{gN?vhub%yy>PeL1=zCpkNCn>hn zhhn96R`IeY*(lHhd8-E2-_VoH`KbdoG*5Jx;7Kf!v|(-YS2n7}gJi~Pf%R5@wqL9V z>0hG>n)1(B_c!!D@4Co%*xJyb+ zuiBlgIidkt3VwpF5O;DUS_A4rXE3@C-AS-e6J$-!GLv?@lMAX^pmFUrb4kse#QfHR zjoCqrP{o~0Q`CW=qp3`vA~)i`SQj)`{a`wL-AK-PJrL|}Vn*F`BR1jsV0f*a*|f=x zwDzIzUZ9ofob5(bO^x7CcMVe^Tc56)p%Jp4#zb``6z`y)|VV+i9TTiCaYKa#n>^&!in zoh|J1k;Hk^9FsJ&j)l(T) zKt9x-ZJ6aupDQ%MVSyzZAmvQ_ay4L5vl{E3>O|Df)AuTul0*?7oJcGE?3;bpBe4Fw z6Y<+ZpHYV#6TC5SBCFnMK!s3+c{;&~tR1ZhesWtG^Og_9h0bb;JNp+r@&^;J8mI=J!K<IZ>X@B@mD;)?}tgLQfM0?T4>B5Wt{nYzR zQHG3x`cN~lzxwxIN}#gA0361tsP|7)f~AiQp>3+7dc<2Lco}8{Qw=25vyRiB=NiMw zdo|3EHA*lq(*!ImQ<&9*mEf+IDU8qk#LO&Kgwt!ZpzC`#Qyr)bzn^HsxF3DgbL^EN zLRJ?#cB`u2`cD~>Z|OnFoKfnh&nfd~QR#de!u|h$ch(Rd+e-4+ZP`Y!eY^yJt)gZE zftJ66xIbfRL+_1c&HVNHO!`jpLN$MVLUjZDKla``N~#lR?zIR`N3oOLi@&X_W&%Ww;j^BG`o%O9X zbJn-M>A&u^*Y0|1|E@~As`g!3?~kK?@qya>rXAjh`ocX2=EqHJi2AjW`{#$Wxi9Kt z+8>x7H{$H5|9s&=`R&s-jC$lwgYp}uo>#|jUEXz2zWK-%tI#ti9hARybhB#oc_RIoTp0BW z9s1-eFSR7PxmH1QC~20FX9vRXP@sue4^gz z-uA>N>iZY$PJCiaUYfN#@rkiI{h;>5r=I-3K6DS_6LtUf_98w}|1H~x_(c87IUR{l z)T>|InfOFKe9x}LC+cfH4ErvYS`zi0`}ZI|4WvJP*DyynyQKAq;QGu^uA1)9x*Gjb zC~wXFzGl=5Lpfah`3g}VAIj&|p?q?W`%KW)FZ9Zfn6_@bXO+YI)qqWqqjb_Hoxzv4t40(Q)=?_*BTae?fYTAci8h$&m7l3Kdt7g zsCysKFTZy9vi00Qe^#G->e{WMZoXUZd_vcCqJHg~&_^#=FY0f@y!65at)t#{=k9r% zzH3FjLTF1TwO=vnBe(C8Z`*uvOn-~HVNcE)??yd)R>yqexKUAG*rH?JdaHAz?r>Iz z{IM}>N8PV8&H_p^$+pHT(Rn+~gqV8uE zbw8`9`&mWZ&noJER#Eq}in^aw)cvfY?q?NsKdY$w#K*c%e60J#$GT5^s)=)``@|>e zQ1^*X)S>PZpQuCKCq7Y!x=(zf4t1aSL>=lr@rgRrec}^!sQbhxvI}*e_|);cq3#o( zdUUA!#3$-d_lZx`q3#o(s6*W+K2e9dPkf>db)Wb|9qK;ui8|DM;$z(>K2cMCJjds> zJ9}l;{mVD#lUer%UfVab?tlDozs$NnWt9OLd(6o5T8H$=towUD(=D^^U%XS-%({QU z)Xtf8f5J_jGVA^^w{*;``-|S~kXiRvIk-b+-QRh~4w-fT?QR`1>;7h=J7m`VUH0#o zS@(bK)G4#>pLTrb%(~z7n)acKKEw0#`f zJ`QakhqjMH+sC2pt{R$zKQw*Ht7nX9i>6OG^vxZr(DW$}U3p>D^eJcUJSuAXluq)(Z>!SJZ*QyzG+ zTh#O^%U(1qK0AHNO>Yj2nm&d2RF|Vt{PW&{>OVo{qAbL>h@c{ed&5t!}#9ws-y1vNdB~Ad&;n5 zd$ePFv}1d;V|%n?d$ePFv}1d;V|%n?d$ePFv}1d;V|%n?d$ePFv}1d;V|%n?d$ePF zv}1d;V|%n?d$ePFwCx_ch=03^__wQwf4hqKx2uSMyNdX?tB8NQbIS2=NBm#8xp%(9 z=wIqruNzpu=-2__z3a95Ro2StJ8af1Ua$Yt8FlB69hgs_a&rB%D{WZ+^;h~vznO^D;nqD_e7 z%%V+*h~vznO^D;nqD_e7%%V+*h~vznO^D;nqD_e7%%V+*h~vzn zO^D;nqD_e7%%V+*h~vznO^D;nqD>$^u}z?@tBBQq+RuO9e#UY|{SEC~ELZ5z zzQuBd4((ekSLo2b#d3uX?OQBY=+M5!a)l1~HUVv$fVNFQ+a{oG6VSE^Xxjv|Z35ahp+d*^ z8e>IUVXV-`3T>>=#tLn$(8daFtkA{^ZLHA73T>>=#tLn$(8daFtkA{^ZLHA73T>>= z#tLn$(8daFtO}jJFZ;4fuYB6QrEk#AJiT{*XWVNE`Mhohq&c<+Gx=o4>^ddaW-^PU?v zM*Y<`{qyZ^n;rGD?fd2P`}`91mSJxH%t6anlg_7q>XX0!{Hjrp4||>;d;CvP@6n`J ze)IaRqYg2NXE$@d^Sx;2d(qDKqMh$WJKu}`|Il}Znco#2^ol$z~MXyFb`D`=sE$`bV9z=>_+5_vw@!TyS6TPRHz%g8N># zcFZm-xc9!MV>Yzl{{5JancRO}rc);OpD*Z?$-U3kowFVV_alDkoXP!$&%0!D-+X@8 zOzy|7)IF2?ExY%~q9%&hjy+H?OY%Fsb2z$1)z9*fxZ?CN4 zds3b^ewQ82D9<*Ty>30}(?^LoC^4jy#b$J_o;$9LJm zLm<2Lr>S*(mwnESKT|C(r=w=zRM2Zo@Z(bcMS8f;d$Het$pzK;CaXMt$py_<$3G))_%1x z{tVAs$G7$?bnV3R*72?VCC7B;dF%Mr{^J+A@VxbWYyU;(Zai;2-`cPFb$6b(o^S2L zcj!ECeetb*WQu2kOz}*RDV_;3#WO*scqYgc&jgv`nIKa<6J&~Kf=uyDkSU%CGQ~4N zrg$dE6wd^i;+Y^*JQHM!XM#-eOps~enGiYReIZA@FXV{#g&gs|kR#p~a>V;Wj(A_l z5$_8*;(Z}Uyf5U4_k|qszK|o{7jne=LXLP}$Pw=gIpTdGN4ziOSa@GVj(C{J5f2kN z;$b33JWS+>hlw2VFp(o3CUV5XM2>iv$Po_{IpSd=M?6gAh=++B@i37i9wu_c!$gjF zn8*3<@uHCh0$q`Q>IpQfKM?8h(h^LSo@f4CH zoqAvxkHBu6}jN@-j(9`K5pO6t;teH7yrJZXH&1V0Hj(B{@5sxo9;_)R%Jig>uczi{Uc(ut9uQoa2)h5So!K+P< zc(ut9uQoa2)h0*0+T@5=n;h|KlOtYja>T1mj(D}n5wA8m;?*WcyxQc5SDPI1YLjE( z)fPE+44!*(#B)!Mc<#v&&pkQfxhF?F_vDD@o*ePqlOvvca>R2_j(G0L5zjq2;<+bB zJon^?=bjw#+>;}odve5cPmYD>UgU^(q8#x~lq24Wa>P4Pj(8`^5${Af;+-f*yc6Y! zccL8ePLw0wiE_j{QI2>g$`S8GIpUotN4yi|hm2c{hH zz?35%m~zAeQ;v9G$`KDtIpTpSM?5g)hzF(|@xYWL9++~(15=K8V9F5>OgZ9#DMvgo zBl_Q?Ca>SEXj)f;}QF$j(7{p z5pQ8R7T&^fq>mLnd~a>OHAj(9}NvDsyX^eajKAZ#m-iEl0e*<%rj}9P#>=BVONf#Oqs*czw$euWvcx^)1K3>pOD9vt5pO zw#yOEb~)nNE=N4u<%nmy9Pw-IpV!9N4)pti1)r6@!pps-urUIdtZ)t@5>SIeL3R2FGsxh z<%svb9P!?lBi{RR#Cu>^M zD9DjB6y(Sm3UcHO1vzqtf*d(RL5`fEAV(I13|k}NOcObBrimOm(?pJ(X(C6?G?61`n#hqeP2|X#CUWFV6FG9Gi5!bFO(I9mrja9O z)5wvtY2?V+G;-u@8aZ+{jT||fMvk0KBS+4rkt1i*$dR*YkGxIb%qUoG~Ov&KQy-XAH@aGlt~I8AEd9j3GI4#*iF~Gln8Z&We)bcj2rkIdWE% z962jWj+_-GN6w0pBWFd)k+Y)Y$XQWxp9Pj-0_KN6z4r zBWLi*ku&(@$QgWckXDP~&vlQjXS&DMxEJZnTmZBUvOHq!?hqDyr$XSYVXJX2cGco1JnV53qOiVd) zCZ-%Y6H|_yi77|U#FQgvV#<*-G38jCi5WR^wy7LB+f1P36eh zrgG$LQ#o?BsT?`mRF0f&Do4&Xl_O`H%8|28<;dBla^!4NIdZnC968%mj>Xxgkt1i+ z%8@f_<;WSea^#F!IdVp=966&_j+{{|N6x5~BWKjgkuz%L$QiYA^eAmZ{7>v!uXwL zP54H}?=-It-_H1*=DFdUnu_l&1wx%JpLJQ_J;Yg+a|zz3A4Zd8!wi{Iz+i7niTwJk^U!mua5r z#oTYo_2P^f<$AHybLDz*=|kmu@!{}zc5~$Z#g*mu?VD4}?b`zfEuZSes-2ck^`dHr z}$Ck^6^ow=*^X8S?xAmr%+qci2DYtJMKU{9#7GGa(-wrvW+`j#7@N%hM zOz5#(suz9RESKuVto4^m90xTI=SLSD$Nw77ZjSBSvtO6{sY%nz{nR4bU50?9> z)vhb|QE^pTh_8#eRH?qM_uf%xNDbXQ~Or)mt_;j z=a*YHas2w*@_6ImS>^FY!wco{#*UAb#~V|JmB$-5o>LxgOh2ML-Wb(;nbf|mUcF3e z-&$?FOyYRTO3NgU%PuUBH?I7!Jl<$Exjf!DvM!$8966rwXnEW?^v3eIar<-1VOQ(Kn*v29Kf@8}SmrfiX{INW4Jnn ziF(m*3;I?B67{s~_*yB#k$^ zZPp}lJav^OiQ|kP%kObly|g5~#|^z@NqUbPedLn#9=FGCOVWGXGp&}S_qY>3Ex*UL zdvbAlk85+u;`AQ3c;Mpn9`~2+7N_^Pt(z=P?{RHjFTclqId)On@AT76i_-h}vPUmU z@8hRri_-ge=aqt|bg|#*_7BVN z<0rgPejnfXzTeXO_`H*UOYh@zI{cR2$49OETY4XV?VIxZ`1{ZNn%>9fT>EQ!A0K|w zuRde_hylN*d6jWn{hHp#H(gYoSNZMLU()+{kGp__lx>CEBHt| zZd@(+NIP!4FJG8AZg~B|#PRJz7N+;{J9k=`INsW9Vd6MwR(W3K{E@!x^uJv=`c-Y+X{Mb7UKP8TjUiDMr*ksU8X&m7){kjk<*i;nrg@c%H~KMg-1mp_{8+aae@Gl#-TFh~_}629Nb@S~ zcmE-A?6%4eiR14J;@QoyKDKzLJkPoIBi|>Em!0{2npZin`}c|C=)ZiQINtt4d7iWP zqy>rNZZ|JT98W!BLE_jfTaY+jwCaMyvCSvtdCsO!e3v*by6C&aal(GzrTX~kHs2+V z3l^8>ITua)HgOy|=G(-v;l^(h$Cr=%Hr2EA^>yMn^ULzO!x0U06UQ&FotrogKX`7ckAwd@H*p-a?A*k0(|6134jmu+ zDsk+4_E)Js4(j<;;<(C=U-^vHe_r#e#BrOi%IinB*Uw2DPrPzY;yCfZIjKI5{_C8? z@vvrLU8CUG`UwgZ}4*32x>1*C;NY#>f^l4K299Z`mMa4`}?$y633Buf0Q^5J@KPdA5Y%8%|vE%!R<0i|z zpE%B)QC^o{;nCnDUF`8*=d9VOK5o)ucH%gF``JEY^{2sW+V_qHUzYb*99;Ka;<)P- z?X6@xau?@&41Mruw*XkEw~{ zJAav)INtSbdH>;U!FSqu&Vz4yHF3P)$X8Q+ysrAy#PPNjUQHak&yQy}$ND(%&GJ6d zBOZJuahy5yl~f-`c77#sY})#j#BtuY<$a|0PMDH7Uj2_LiQ|ihPD%A~K-(#afJo4k}bF8@n;Kky~5 zPD&ix-Z?38T>AJ)sXi{*V^ZQcam`7Iu$Ac^CWD_%?-M;-g3&sd-LelgX@ zS2leyacsA+ysvxJ$rBUD!M9FK9QQqbVychJ?iKbM7xnSG)g~s6TYOgD*FFB}7ZS%d zSG|xp&OPvjR3D$%?uEqh@un{%j;Bs9@9Vzlp$UoO{ijbz_3`np6B5V2Z9BndtPbCJ zCXQ!)Uf!QS@2Te#$LBA7K5<-g;Pa_IHr@XD#PO-6!oKl><2`Sd_vgQR-*buMQA3|g z^>I$O=Mu-;{`_3x`1kqc{rLw!_iW<0`Hjyej-8KqHr2=eRnI1l2e*7SacuQXJi9s8 z$MxSRe`m4X1J5LmcMN$Z)yI=MJ(D<2TIZR>aqRr^cNT{~-uF#k`c7MP8oyA(C^2Bkq^YX-TX1_eu$6q(k6UXI#Eq`aR+LVUGal&H_iR0_n zH6)H79vb|pi|^O=-L)Zc++_KN#Bu1mo4dvKGnzTHW{BdHvPH$-P80*PbZFB4u3jvT=Tf6Q+=GWNBAD6sE^}XJ)Jmy^GW%; zr*ocqDsfzN#Z!sn;|DyI>f`C#K9xA0+T^LkvEAF{@171AF)ndD^0aZOKAzfTT;jOt zHsgH8>YY{{mpJbAS^4|5vE!ah951=#$;5G1?USiKPTKa##PQ6g;k&AWf@-cPb7|iTkna)ajS32->+@BLHr2=0ZO0~#o3$95 zIKK0BJi9s8$Io6Xe~0+PePa^G!KaQ%^|5WoF^S`qYmZ4BhkjH34sqMyO)bZ@uOFQ_ z_Bv#As*fMn?0U5zPhmd9pa41 zqY}r<9vzi9-gND##PR;Yqf&ibW0z5h<5$f_C62qzEPqeB<;anV;|J%4?;Hz`FZUXm z>f_QIjZ7SG_^JFo>8ev6OB`Rg?Xkr1>SG>D_3`rEA4?qfUH!4d@q{nR-;vPTogs-qwE8S6Xk`)I0<12%p%ah&vH`5WO|UwkBSoPYBpiQ}we9!d4_+V=};t`4CT{R<8eY|p;5sBlT zO~N*0B;Vg33eK?EUeI}em?mRPRkz1ZQi`;!CoJH<9fwRb6zvC=&=R-J) z+s=7`59E3mg#81#-UVU*K(2Q|*dLYaT@dDfa=i<}{-|8~+DrAe394 zu^#V&P;Pm~db|rlx#bz_@h%AEmS?QPyC9TXp0N(^f>3UG#yY$ULb>G`>+miJ<(6k0 zk9R>Rw>;z1co&3n%QLpcyC9TXp0Nt=f>3UG#wxrELb>G`tMD!e<(6lx!n+`pTb{8R z?}AWndB$qI3qrZ&8LROw2<4V%tS-C@c*bhH3*?A*fgJHJkR#p&a>Tnpj(8Wy5$^&y z;$0v|ybI)rcYz%7E|4SM1#-l@K#q79$Pw=XIpSR)N4yKTnpj(8Wy5$^&y;$0v|ybI)rcYz%7E|4SM1#-l@K#q79$Pw=XIpSR) zN4yKhD$Pw=XIpSR)N4yKTnpj)iwYTnpj(8Wy5$^&y;$0v|ybI)rcYz%7E|6p4T@X3qT_8ui3*?A*fgJHJkR#p& za>Tnpj(8Wy5$^&y;$0v|ybI)rcYz%7E|4SM1#-l@K#q79$Pw=XIpSR)N4yKTnp zj(8Wy5$^&y;$0v|ybI)5co#&Dco)bK?*cjET_8ui3*?A*fgJHJkR#p&a>Tnpj(8Wy z5$^&y;$0v|ybI)rcYz%7E|4SM1#-l@K#q79$Pw=XITqdpkt5y(a>Tnpj(8Wy5$^&y z;$0v|ybI)rcYz%7E|4SM1#-l@K#q79$Pw=XIpSR)N4yKTnpj(8Wy5$^&y z7TyJsBi;pa#JfO_co)bK?*cjET_8ui3*?A*fgJHJkR#p&a>Tnpj(8Wy5$^&y;$0v| zybI)rcYz%7E|4SM1#-l@K#qlXLF9;cfgJHJkR#p&a>Tnpj(8Wy5$^&y;$0v|ybI)r zcYz%7E|4SM1#-l@K#q79$Pw=XIpSR)N4yKhD$Pw=XIpSR)N4yKTnpj)iwYTnpj(8Wy5$^&y;$0v|ybI)rcYz%7 zE|6p4T@X3qT_8ui3*?A*fgJHJkR#p&a>Tnpj(8Wy5$}S;F?biq5$^&y;$0v|ybI)r zcYz%7E|4SM1#-l@K#q79$Pw=XITqdpkt5y(a>Tnpj(8Wy5$^&y;$0v|ybI)rcYz%7 zE|4SM1#-l@K#q79$Pw=XIpSR)N4yKTnpj(8Wy5$^&y7TyJsBi;pa#JfO_ zco)bK?*cjET_8ui3*?A*fgJHJkR#p&a>Tnpj(8Wy5$^&y;$0v|ybI)rcYz%7E|4SM z1#-l@K#q79cyW7Z^{x3yde;1;!Ka0^^Byf$=Q7 z3u3*%yTE#ZcY*Z+?*i)u-UZeRybG)sco$eN@Gh`k;9X$7z`MYDfp>xR0`CIr1>ObL z3%m=g7kC#~FYqp~Uf^9|y}-M`dVzO=^`h`Di1h;R0y*McAV<6lTnpj(8Wy5$^&y;$0xe!n+`H#JfO_ zco)bK?*cjET_8ui3*?A*fgJHJkR#p&a>Tnpj(8Wy5$^&y;$0v|ybI)rcYz%7E|4SM z1#-l@K#q79$g%J)h#c`QkR#p&a>Tnpj(8Wy5$^&y;$0xehTvTwN4yKTnpj(8Wy5$^&y7TyJsBi;pa#JfO_co)bK?*cjET_8ui3*?A*fgJHJkR#p&a>Tnp zj(8Wy5$^&y;$0v|ybI)rcYz%7E|4SM1#-l@K#qlXLF9;cfgJHJkR#p&a>TnJaSYxC za>Tnpj(8Wy5$^&y;$0v|ybI)rcYz%7E|4SM1#-l@K#q79$Pw=XIpSR)N4yKTnp zj(8Wy5$^&y;$0v|ybI)5co#&Dco)bK?*cjET_8ui3*?A*fgJHJkR#p&a>Tnpj(8Wy z5$^&y;$0v|ybI)rcYz%7E|4SM1#-l@K#q79$Pw=XITqdpkt5y(a>Tnpj(8Wy5$^&y z;$0v|ybI)rcYz%7E|4SM1#-l@K#q79$Pw=XIpSR)N4yKTnpj(8Wy5$^&y z7TyJsBi;pa#JfO_co)bK?*cjET_8ui3*?A*fgJHJkR#p&a>Tnpj(8Wy5$^&y;$0v| zybI)rcYz%7E|4SM1#-l@K#qlXLF9;cfgJHJkR#p&a>Tnpj(8Wy5$^&y;$0v|ybI)r zcYz%7E|4SM1#-l@K#q79$Pw=XIpSR)N4yKhD$Pw=XIpSR)N4yKTnpj)iwYTnpj(8Wy5$^&y;$0v|ybI)rcYz%7 zE|6p4T@X3qT_8ui3*?A*fgJHJkR#p&a>Tnpj(8Wy5$^&y;$0v|ybI)rcYz%7E|4SM z1#-l@K#q79$Pw=XIpSR)N4yKTnpj)iwYTnpj(8Wy5$^&y;$0v|ybI)r zcYz%7E|6p4T@X3qT_8ui3*?A*fgJHJkR#p&a>Tnpj(8Wy5$^&y;$0v|ybI)rcYz%7 zE|4SM1#-l@K#q79$Pw=XIpSR)N4yKTnpj(8Wy5$^&y;$0v|ybI)5co#&Dco)bK z?*cjET_8ui3*?A*fgJHJkR#p&a>Tnpj(8Wy5$^&y;$0v|ybI)rcYz%7E|4SM1#-l@ zK#q79$Pw=XITqdpkt6;C?jJzAe*o?N0kr!E(C%A67vG6T?}G6Id*pf-)W6v+*Snzq z1zmH!3wn0%lIvZtQ&s0&?}E$1_s)73%saPZu6MzXA9u+0E|__8hg|Q1Uez6Py$e3x zsY9-J!TRBwYrP9PKi47GyWsgg9do@4Ca=~h*SlcRHJx(33oOrg7g(P0F0ee~U0`{} zyTI~{cY);@?*hv+-UXItybCPPco$fn@h-4D<6U5R#=F4sjCXbHi>%g`CYT8&;Kp% zGg)*?mu$7qe~5a8o}IJKXM7#?hpTkTvfdv@ebu=gvYU2zBkF0N?wuVsu_5XUhVGRe z(&oOXKl^--?6?tUN4?X%?X%mbZ5Z|a3wFM$W|u5@FY47V?wq~U?3<{E@7XoG z{m6w;U-MzNY~`hvM1AM}J+gCpH;plwzH85H+U$}xKE%!Vpp6gO_@Ips+W4T258C*k zjSt%Rpp6gO_@Ips+W4T258C*kjSt%Rpp6gO_@Ips+W4T258C*k2aet~mZc`)ulKy_ zsQW&WKfT}b?V~=Ys$u;3AMX|QyQ}r8d;5TnrR!IXtIH1R67?Pjw5;E6TDPc=YqeMX zPPg`m`i%X~t$*u@o>4!w3V24c7NsIsA)I4E;l4<+Kr8uKQC(9jb_i3H0{Q( zd!7-m({7yi*b!0FZtQeu&!}lPE*`v1)U+Fms+vblyD@gm>oK3S8?!eU9yRU8121-q zns#H^i)O`Vr`@>e&4J_px_Gy2hta=OAGS+l-QcJ8iMsC#o76A8dX|NGzUsZs-n#y$ z4Z6hZBOkf6zOnh9@%q?12GyT^NOd-S%E{HYzIc57#IF0q>)S87ss6*4cZ=6McDTI0 zbJxPJHL_K4SO&bz;U)bUxo{`OkKOsAf7mT$j%yuR8-kC;w9=@j{?CqG3x z^`uker=I*2&r;8`6#1zqKgDy^^IXNV)blKXdrtpC{wM=~(6LN%{Xb>qzm}OIZpJ6C zh)-Tor}BzAl~>fMyrNF!6?H1Fs8e}GoysffR8C)9)Tz9pPURJKDzB(hc}1PdE9z8U zQK#~XI+a({sl1|2Tj-CXrrituROx!?r$YY~HSOdd$}rde!zI+~f5Ij75s6Fe7YZ)1zbLrG zex%?M`~{(-u|F!f#D1#a68o<(28;EA-wI=}STE3F3>NDJI*h?$y+DUCSgaT5 zFb0eD0v*O+v0k9V7%bKcbQpuhdVvmOuvjn9VGI`Q1v-quV!c3zF<7h@=r9J0^#UEn zV6k4H!x${q3v?KR#d?7bW3X5+&|wS~>jgTD!D78YhcQ^J7w9ksi}6Q?F<7h@=+O4& z^fk1-p-qmOHaWD_VSN8uHEnfh!{c?@@X)r$>$L5m&Cls;X!Ao~5U^nl=6tB}a73svjrpQn1JBoB--&Eu$_BF+`#D1j6 zPwbnD=Zbwz@hq`Fs%#VP9@>kt5#Mosez!MeBkGmf^rdXX@lwC5`cXEb?l_}AWh3g7 z)~umyME&9ewUmvhFWhq=Wh3g>M($79i29iJ2U0eo{_}+gQ8uC;xzixZMjc!(?>dOG zQH7p4=^)BRHTt}f2U0eo{=NADl#Qqt%-N5!5q0f@HI$90cfY$oWh3gRKkZA|i28*N zeJC4IkA1lpWh2(Xv*zzh*@(J`&wtUpLm4-;aYGw7v~fclH?(m>8#lCZLmM}=aYGw7 zv~fclH?(m>8#lCZLmM}=aYGw7v~fclH?(m>8#lCZLlYmrt*CyXSAN8_b*s6)%He(T zd7rKx^(zbd=4;>FJnGkK`sZ!V{2{)#UVF`eyk^+cs6W4|ChvI5JyG`y-gg^3cu3TH zPOQxbPy4AYX|5N%@7@|Tv`x&zyS4eQcaI;B-ul$q{Jx_))S+8Xsmae@Ygp8^?+?iL zANG9IGspGMPpkPV>fQ(R%dZ{2YqY(T z>>l~T1+AmrcIWPSo4#vBy}~_R^GWSjjQYs!yX4z8UmVllVs4l-S>xTPXV2=GPaHQY z>I++R%v*1DZqyyl>X1J+X6>lEx9O1g*{~`;%iURrymix|@p;#|szd(LlbcuZT!S|5 zm``qdNz_Xgcgzo3Z(P*QFL6(|&Aa3?e)y^CvHM%*L-*~P_k3WP>W9v3nJ>DuTmICp zEvpai-75RVl!RNnOwb$w`@+%+jmv8vq z6II)M(mX%l!2WstlIyB&d%Su6#tr@Qo5zfbdiVo<^ZBbzj{2(G`sA;jH9P7yXZFs| zJLT)BpXk;re|Y$hQLpjYzWJRW{9M)a$>#aJXYQNVocK#s@A1uJd3&_iuT@v(&GSR& z^vI|Fu(0aN$<6cKCU(z9ueYG;@wc1jH$K`ee`UkZtLBDph^F1wHNR!Qx2v}Org`3N zY?u7nb)T&|`q$?9v9mkpTQ)pUbz`#@`EQ#AuflsTtGc^Yi+t~4o$@Pw?_G8EpIhWj zHtUp6S$U-(Ykux`AJ@HoU5k9DwYufioBdq3>g_G^0ULGC7hSM){q7@L z*oK^BLC{ke);`JzhC#r zlJMQor2hGeUrnqV*rH|r{N)4kSJ!yBuIU<~9ow!Zf3(*Xb+`VdW!`^mP5yb0zI9t} z8OqWcwfVdKR;qh!r(tcINX15|NPsrbE-DKu4O*ttbY0MYnxObersq;FX)?Zbb5>G`$Cx? zF|<$K>8w`Oua0V&Pd%u2o}c@t>Nm!>%;&W0mA5&nb@lxdO7nQOS8E;8BeT8Q^OV=K>X=(PX0}(0f}gPM)hY*f$ZW56-mybwd-Zm=4w>!M zW}`b~wpY9C-!Zej`n6N1%=YTE<2z@zS505;lG$Dj?%FN0z3MWjduDre{!KkI+p9x5 z_sVRqHd)X+v%TtYQQyq=>dT+{WvRVtHz2dUI;Cq(W_vZQb!}#QwZg--neElG^J_EP ztI>19Jwv{%iR^vi6o-kshzv%TtfN1x30>f(XD zGux{(SMQbCUhOljXJ&h~#`Qfi+pBShbkA(B)(Ek(z1pB>*Ua{6(y3iC+p8a6>YUkL zop(c*%=T*hxm`2cs~0ctmf2pd`$+f9_Uevzdt|m(*`7T!+pEVP?wM7zSDEeAysTGd zd$q>Fy))aZhSU3GwpSON-#4?pYIbtJ%=YTj&iymntC}VKGux|`t{;%uUiEHLli6M! z+o>kAy&8FVO=f#F@SvK^_Uf{&YBJlaz3Lk3tnF2YUpi&BSDhzz&TOyV zd#Fohdv)c#T{GLOhevkHY_Bey)IGDkI^wGyneEjI8(h`MJ4M6A;k(G7!+5J2y~|zK zr|al-^B>!B{eyv5{TJ>1BQ_nHuA{TZC&v4|UKPIeMlT#Sv7MSU)n1==uMfJ@j3o_U zUO1%j<)F9Qs%buB(vZd$;kS;zeX0DHUxqaH3VNwF%j9pYJ+$%mpr?JaY<~PkLmOWX z`nm6#<@_%B;dd`@U3!*$^Je+Ei-*MP-40(SKk3zyzHGu$`G=R6bk?zHKDA9r&t0^n zp?>D6@%{mG7ByUPd`ZtA^n1gxO-lNX<9}=DHe*tCH>>~Yd3B=ucS9UV4cQ%yF=ssZ5!5UoOWJGcU@`S#*aTN>Dl|P+t{kh-{U=V z&s(=~ySkG8@y>M{r*3mtiqF7#r~E(kgxTvip7wL;`XRkGXuM#JQ{z47JhwsPwH-?O z@hvxO-0-rJo^aWQjXTXM>9=QX*x0dZNWA~BKX24H^xl#_x#vcW|5$BkyngmE8#V59 zNlD)}WTVDgwkp*Z^bv=aH1`a-y`=fymES07(!8ZBSO(CR4eqhb@V}NN(zJ~6Tb4cYV3{OumR0g>8Rl6m=RBjDI9M0Z))8W5-64k7 zDPn6~Bj(mYSXehCHHx`ZXCGZ_>hiqBYoq^?;2p@%pFb^+%QT zMdzNDKRBtRAHVCg{Q8ZKjQ4PT?3pFa{e505Y0{aq?osg`(%wFkjVHfroXL;zC!ca5|JE;_OO8CRe2IhHiI3%h zxLHn!r{#w@Tds(|;1&Rbcm1X6E}aCc$y#LY(9y<`G&AimjSuMc@tqJC*d{ z?SF1qaCS+5vF^f#;ZK$HE=MhF*yG#s_3byiDE=?^*Y8)-q|^Jdk|zC2N0&6eyV)Bh zO@6ljs-(&1mkUdp{Lfxg(ma>f&pGqMbpO>W&Q9sf4&RHV^yf}bzq{h$Z>9WfaNrva z=JUGQ;hUWz|0^w+mY(a`d#0u5<+^d;e&a(r#*Oq-Jj3rAXYynG$){Y%|M%aO_{Qh@ zsib+{yOzB?#*jEXv|dRQpH91#G;urU?Kl{D$hZ+>OGpY%7~v84Ik7kZa8`FZuok|v)QpH|Z3|BSOsn&rhd7&0;&1-p;&Z{v=jFO_;C|ynI>wFkQ#`}(8fWrj{K@B+ z1sC#v!bhjYnDAT!=aw|jJ7xLP6R+8AN}BkrdwNL|x658GY2x|hW@p6viSv}JOPcsU z^m|FeW#KVr#(Ut^>4TEy`lj8_ir2Zn-4i8EI)|@%cDzpd)Bje|{O;=amNfa<^v#ln z*NxwnH2FXG*OKPByw3A_KXEV};*-)3ar1YHr}-hy=9BoFf4KNu@bY=NZXCGZ_>hiq zBmET5@VmyD{1|`oDVIuKTU_<$Mz5c?_|J{rKj7%UG@8yaZ~mpx^l#aI{YHOxx%1X< zG(USkzkZ|n?7v|BM)N;uejr5HtziXVykMSp;av}fn z;<>#3?z(?Y_y7LbdMTaHI;@w{A3vvc`rWR#v`+b1sit+x=kJ@fPWivGMeFoj_cUpp zo|o&!f%}aQ=@>WCH=g{iaV9^;pM1)N{M#P#T-H0D*ZN2ttf$1s`b*rb*TmEMPMmEA zh`;RvTx>VsWqZPP+Zpb+{UIIOCDOOO;&*Mw$dBzC`Lx|5|F(xbm)Ch-?8KU{n+c=^0sHxAryd`QQ*k-qWdca1aoG5+LJF67_w2G3=`#`D_W z5eNH0;$#0v-0U}rr~N5$wx1>bjyK@qcmrPc*Ic(B=YGc9~UYJKl)puo#E%yxvb7Oo#ZGK5_GRiKqD?&gPT&n}4|YT=4RFxo#Y|-}sP@aU*@> z$?qCx@?-qTr(DRt?{~bn`X0gitnU}R=lb5k`>*dKycheP!uzuCFT6+lUc>vi?{~b9 z`+mp!xbJsd_x+CheZM0e-|tA@_d9;q_dD|A`yKi8J&yeQe#dipo%dPq=RMbSc>gth z-i!TR-j~e}@6qOy_iOXdd$-TU`?$}`b>qPO#)ou_8|fQQe%CmYALCCxgICow5^@)wg58E&5Y3rWUc-R58 zQFG6kw@gUaonzdU})gF+Z=I ze@f$s9rsLng`N6E-R-zj8V}s0ChA?LTy%k8hEyp8*K zO3L%NHKwFz*{I#iF`oR^cKc6Gu|*Sq;{4$?Q&UXtKVxc&)pfg1O)(rY`_&ZN-ZihL zm~Z>UD~ZMOKTS!D9@uC~Vt4FbFDKUgmStdc(3Xvjf@U6@d^)Ecbup)nc1|1ZoHp7y zZM1XRXy>%i&S|5a(?&a|ji&rpuFFskxz1V`vl+GW7B>+q_Xka)a_H**kh^fQ`zY9(d*1ZdO!1%XwqTc5>5KdXQKIC<~h;ihxt!5`D9)cP5zlL zMY|q>W?ba`jF(J@ag^yZzVde&cbOl?W9E}_n)!E~h4dNM`Mg{=4%}~iNXNL5zVYOD zjWhW%{^XPSQu8k_=eN1eJgWCIziK+nyP7`pvHmXewC0ETTl2}huK9N!nDm(k_IbH( z9Jt^3kdAR9edEdR8fWrj{K==h$iKXt-{yCj_x66~!%c^Ia?@x2+}~wh-TW}$Za$fZ zH~-GtlRoqIJ}=je1NR#r(lKtNZ#?;3<4k^xKlzjw`DgB$-=beYGtR8km2=&d+Ies8 zuhg`Grdg?Jhq=z!tWwiQct5&wUy7PJbM~T;Px7Fq4`rVN*Xd_}KenXl`@Y$wr0Em; zEmhL=m9K>LdhVwWo$yde)3=^}X-U)Pet%p^(-(g;sHEwm|G0O8bX=Q8yEct>Z5r*` zG}^Ukv}@C7*QU{~O`~0#M!PnxW^LMgSer(>HjQ>|8tvLN+O=u4Ytv}grqQlVqg|Uu zJDyjw&j$?)_R^q<6?{`{c77i1{5;zEd9O1c z<^9Y@p`D*cJ3o)+cbShuJ3o(hejZK!nU6yAT+Dl*d0ys2(8Pgx5;XB){sc|jm{&m) zPv%?D#F=>*G`yIfLBorA8?@_RUT2=i`ejr3DI z!|xhr@?-qTr(B$$_qmt{M)SPP52J|#^Tuf6!+bKDxG~R+CZ5bcqlq)~(rDLH(5|PT zT~F~k^Yh-%{5+a;n4d?JKJ)WvewX=qH2GnE9!)-(hewnDbHjQH8eU%KdA*-Fm=5tt z>4&)ayTsG{5NGpA{8?Wheb-aauBUk2IB>u5AsypJ`YE2_ca1aoG5+LJF65v28Pczu zYjPhQ*WE{lb{`$ueROE|(V^W(hjt$w+I@6r_tBxCC~Q1Jd6D@ z&&YZxF=3wEa>D$%<%fB7%N6tOmN(|%Er-m{TRxe$x7;$H&-xnaGtbZZ8rtWCH=g{iaV9^;pM1*2^%~N5y$0=i4che@wCgo!*K5$O z*PvamLAzdqcD)AedX3lZcU-UGy6ZJ)*K5$O*PvamLAzdqcD)AedJWq38no**XxD4d zuGgSluR*(BgLb_J?RpK`^%}3+Ke}GSb=PaquGgSluR*(BgLb_JP5vE!#^(zA5V+3s zvL1&f4vve659@baCvL3kp^2yCE8^_9i}!E0#%j-O^_Y()xAwH&0-27eQX?}>a`6T|Vhmt1-1-}sP@aU*@>$?qCx@?-qTC+nf4N&f%4H4gUNau4qv?72nrKEj?`H18?wxkdB- zl81foXx?ksbBpGEhdsAw-h`@eBctVol#-QS|kHxKj$ z=8ZnWJkxjhEc7XrYf?Tt{mwC)997Cs$io%el{9%6*1e?3!#!u0G%xq>^kE#1T1=Aa3s|7Fgz=RqaST+;%_krZXTHH@E+E2{9o30Op|pVe~a}X^T0Zhc^eqkkIXac zN(EE)FaCq^~iEaJ+gdKk60h49=Se_c6}V}`Z(J4akT5>XxGQlu8*T# zA4j`Bj&^#RF_KkLzG*T>PWkE2~5N4q|bc6}V}`Z(J4akT5>XxGQlu8*T#A4j`B zj&^+MW8<6dWd-1}J{N4q|bc6}V}`Z(J4akT5>X!0*F=22NU=Q{I{tf!-y zpJbgK&AcV+?`Y;TS(isM&uM;`|1_V>i?Y7YJ;i{CS%U)yER zsM()z@fI~vvp?aQztu*~z6&+`F6LZ*K)lXgi<@uRFKVt|d+UUBzu!x8PutbY-%fg+ z_eAnTtjwF*82)jeIkDm%-!avvuDDxF=irH_G^)GbcuM0r`|KXCvtG$>(HB>)U8;FM z^&a$p7hA7;5BX6W+sb=*@8-Ji-Duyt(Y|-1eeXv5-i`LX8|`~HnlXmoKQgvqZItV1 z)<(UDwNd|aNlJ&^?!gcBbeKGqn80V-NhuB9~YVNV@@xN*~TCOU!>GNA$ zCrvcZYxu=$%Ee} zlQ+LvCeMD$%(MKF9r+>VmPy8D=vYrHG~+|>L0e~OPt^P`+W%E^kL9qkFW@@+7RZBp zPSEZ-LA&P!?Vb~~drr{qIYGPU1kE_MGS6!AY29S3Xq{yYXvh|IuFqXzxA;B2^#ayv;%5D=)ZAmaGEIJ$dn|k8%`!=zEvr0> zWteBQZ1e1vd17K+AXe59VrbnVw$>>$?-%63_Y1V|7iixv(7s=weZN5aeu4J=0?o7h zF(zCm4!lF5eTPE(4u$p|3hg@-+IJ|l?@(ypq0rP3+r~ex#q;d$uR}8)WB(iF(CcWg zQx~{SJCCMpRBGCM??IdXANNn1CfEI4H2HLV*y^E@X5ZabPn0zK@x0%Bnz#RM&mL`v zX{s4#y07n_?fLY#$eVd!U#NNGf6X&#`n=}N7*fa4|Ej%Ho6N(=^%t>2I+w)I6|X)V#5e)I77l)MtTRWqKgUeJ$v?jT(|E- z+xMaE`_T4%X!}02eIMGs4^6v7S)vX3clUk#E_v{G(e}A$`&_hrF4{g9ZJ&##-FEMy zeJtH@ceHLZEifZad^;M%>2FK+#gSE{3z)8$1iT^*mX!_yB52(>$Q86y!)^r zjSmOC)9Fp~J6<2sxM|DX+D-p(sr;U>S7%hv6T{i`Tdg~^v3(dDjA+p;pA zl4h~rcg*0p!hYX;y5?xV&vpBKwEaHXejjbWkG9`O+wY@^bLDpgYu$fJQ>bYF{N}jQD9D;US^zRxAF&?15Ha}?Roc~qx=f=FU&q6z9 z_;>W1|I_gdj4Jn4q8;=6v+)2&(78GEY9KZjLz-w?9TZR6X$}6m2*VIFpZzXGxEEZF@D#w z=eX40<+{I%_IJ_#F52Hk`@3j=7foz^XK^l<>uB>v8^X6m#N=N!pX_+v-y#qG7TURM zv~$;J=dR=Z|HJQ?D!t~C4sl4|?uBu0(&2jYD=Rd=McmT$aDUoU5%hmNK$J*#N<7^B&X z>wd*QYWK+fXYX-o-?AL33vxuu5iLiw9KG(|MLBX^j%Yce<%pIeT8?Nq>NNp7Jq_Tc z*MWQcVeQ_2w0rx}?(Ijrw;%1^ezbf0(eCZ{x*iVPueXDH`?<%x{b=|0qutw&c5gqL z{OdKrbLm0B^XfH09Q2wXK6*_MH@zl^r}-hy=9BpAHR0ZVe%HPIXs+uu!Towokd9sx zq_5WmzpK{-`7!?FQ!anxRry^;rS@9@Il@|wXgQ+gh?XN-j%Yce<%pJ}*WH6EN3P2e zEl0E*(Q-t~5iLiw9MN(_%MmR{v>efLM9UE^N3B$2x zJ$c}zC(j>wxqldTmD)Y4lw0?*Ql8!8N;!A$E9KukvD6Fq%2Hq4LrXn!FERDbJ-5_5 z_u_KhJ-XcQ-d)mhPcP}a*O%XQ4>0+0Z!r0E&oKFSFEP*Pb>iUt#K&}qTS`B~)8CaN zWnPYGIilr=mZR5=gB-aoN3ca>q{;W5Tvu26 zA*)A+c~QShB~3Ng?SK7tfWE_T2he^yfcDz~wBHV({dNHDw*zRu9YFi-0NQT{yl%hd zw*y@F+X1xS4xs&Z0PVK}Xulmm`|SYQZwJtRJAn4v0kq!^p#63L?Y9GHza2pP?EuO_gn*3Mtvd`riE4BTv94Q-eM9UE^N39<2N3P2eEl0E*(Q-t~5iLiw9MN(_%MmR{v>efLM9UE^N3dL3t_tMER<|1!LZz zT=^~X%6rkHd>H-YSIAQ@c^8a5)lBdDgPyPneE|t@NBv1d59{P{;(|=Si{YUoD ze`F{9L3ud+MD5bIVAM;w{D8dtgC6+}{qiUE%Foy%|6`}}aP0T-QtnL~Ju44a9Er8! z2rG`T;s`5_u;K_Sj8x9WiX*Hz!ipoTIKqk}tT@7oBdj>W ziX*Hz!ipoTIKqmf%9V#Jj+85ou;K_SjSsFZ>On+P5nIDZfGF;{`Lu_4`pU z-`DW_MKIspY>@u`2;bxIdqoesZ)1oM3mzmEj-T@SyT1oOQQzo!K2cb4FVe;=Xd zH@**&KlwgLe&+ii`JeBD{NG3L@mlz8*WTHG(zjhcUNB=p-{ryjE)Ujsd9c3AgY{h= ztncz*eU}I8yF6Im<-z(cPv!dkUVWEGxxUMT(XZbD)^~Z7>$^Ny-{ryjE)Ujsd9c3A zgY{h=tk}W&E)Ujsd9c3AgY{h=tncz*eV3pj`-^PWmw-Y!}@+1*7wV>zF&s*{W7fYmtlRs4D0)4 zm22D~uiw+w_shuW`(;?)FT?tN8P@m9u)bf0_5Cue@0VeHzYOd9WmvI;_5Cue@0VeH zzYOd9Wmw-Yt6bymfAjafeY}*n&_?~HB5l-fEz(BTQ1VjRsNZI!jrz?-+Nj@hq>cKG z$A!O5TKmn_AL6%3iI?&g#g0Bhzg3W_@ z-0?e~Fy;LICyYG53ksu$-wTD&PYw@LFTXDeV-LSO3S+1K-WK-j?{LvBmD49BPoIq^jLxrqjK4?8 z+@*I_uxxIUDsh=HLBn_^wTD#|HR^`hC~(&Re{z)|h{5Rlnm+A1?3L zB^zij-=6UIUSYoJ;P1V{eAB_-dxh!4{JmG0zRllzh3WJBy;qpApx+5+jQp5?(-wQU zE2y?}mMh!1Q!1Oe+o`s2w^MDjd$XzS-0hT4xZ5dTakrB=QWtkS%X^8jUj5xw%JuhH zP5uY?8_JraXk$5dB^zYh5AhpQI!o8@OtMDkcP3%|&LphgnS}K_ldyhg64vib!up*_ zSids~f7jVQZIlhLY=C70EE`Nd{mp1tHo&q0mJKjA`1cO_o5GFtccQU@Hfrv|4?py8 zZ2I3tY54bC{BNh|Z@c*4Nb!HCX1>4k;(k-b|Bec*zjp)ccT`~gjT`?xJFM^A{coQ9 zSl`XjUjMr;V#@V*dH9Y%eD${{kKa80UHcV|{kmBGm>%PIj{L!abBhnB^cdeca+l}6 zDc0Vi=lIJa?>2p2@lLOv;~$H>*+xz4r$5|te9QPZ?vEeVtbWd%p5yn4+-#c`_0O(+ z%J^ZCpZZ{t`s3p_eUC++@Nw;%zS)uaj*s73XB_bx+WKu7F?|g7zsD|leg{DOT{1k2 zOhcX2rE)K$y1d`Kul(OI@_oSf4gb43{`Y(q^cz0NsIM;Q?+~G1zwHC7Pg2)+{S78; z*6#u#b5;5+paqSc1%2D-`>pTK{x^K)EVF^FHE;J`d|Mdbit*=hAKg-xix*J7tt;Oa zJxSiU&42^PNB#4aBd>BjyIQMm^*pO`G35>Ak&*nNeXlQB<;bhtJ!@@LIr?GwLFIbZ zm&-q1KG|tH#SQDCJpM3rX+NxX{i||fA$i4xXTPhQdQ~o#{d$&i#ib#8zj^lU_55A! z^7Ue;>T1Z+Pq}C5r`)sZlKg^va@8xB=U3k|DJ=KZ%3+-*1M|E4)cBlHgYu<+RpVbC zHzfb^go!3|-_k?#{YO7!tY;q@xI`iOHy&$QNQUx1E%{p3a`RgP{N+kBv+H)dC2YKL z%d(t$A6(^~>@UxaF`a{Md^3A((_4&>c;WS|#UE=d8T9bX?|y!z$(;Dk%Hf0KYP`u^ zD~F>WuW|GCD~GGr8fY?-=h>#utsLeKyE04}zeFJ!$`hOJq{levH%@wtCGT_==#&iQ zsqI#l+G3pAXq?(*EP0+yzAEsQWGIh5&tkkxKE^AH@iLD7&tklcW4y8$FXI@CEXK=N z&!R{2DPAT+d5WF%5O?DgU*ptIq?7(*tY?#c`cHxW)K3b^V;l3>AB;w5&MI2j8_r+gR$g!Hui@i z_6LidWGGJ@uqWv;PWp|L9%IQnoz}-BLwRbW$)~m$r#2d=b{R{aXOpjN>_~?46kn51 zaW_u!HBSA+IQ0QzJ&PX6r+CrFY|O@X**HRGyR()K)0$sn2kau%TFK@0YW?dkr^Ur^iRxnDeeN z-m**6aN~-Djs3jQWQ@ zvA5aV7UNaUbz7Y?ExYiVF=pFWcRrcTJ+8)Yy*V+PdVP&IJFGtIy>)GFoYn5`Y{YuE zn*7>p-}7wk z@-UUxsXWTpNj~byq$ldnq(9c1sorQ$CVQftne2@AXR@F6s9j?ExY`S=y|CH~tG%$= z3#+}b+6$|_u-Xf&y{X*Vo8+y%u-Xf&y|CH~tG%$=3#+}b>e}nDTl1&3yJXx$&4-0U zAH5}?J9dfcgvW=59hVuC&uOzq^>?QY4eM=xQ~u=jy{daJH#BT=^o{wxZLh0tJ!D8Y z{f2AvH+RUZzgTrh$i5hy|Nfn4s>fV4INZ{6Kz{DLnbl=i9UOY?dTD-8o6o8n-#jQ> zbm94V-@nYOzP}xApS@}Gy!#4+!tu`@m9KeVi~R53Tov9N+BV-{wdVQ#%MA*7 zhh6ig+s&&!x!0g@~%-=_^o@7>$>=`u;wMBs}CQ(Vw1Xs80Re9(AimU+q1lsNO!TS6wCg>X!E=SO0k6 zb#tNh8`KC9a@ z`f75%Zocms^Xg_rUrkwd>%8-3&9h^puR46yCST*g78$;pwprW!)n7Hw#z$Yh+Wn|} zjcw=EO^&`=tn+F4!(V+`w^8)ffUf7~OOBga*ChICi7hV8cfbFcx?`iS9zS|O{^CJ- z9lmW8QYwo^>ZgU!AnoO?j7TE$e1RU){LK zn7n@WC9S(hUsWHxB~N37v65-Lc&5KeMjX$<3j9g=NBi$y+_>%-Rjp{+x@7r-t($Qm-hU5!{Z9s*?ZLS zh3wyEgFlz;qFn7oUVcE2{DXe^je6xz?2(_bQ~t+(#U-}O`hRLyP;*%|E*vOl&fC|;DSy~xWC=uy1TuXs_f;)Okm7j`OMv0cH%D=1zu zj%9g_Zz&(+Uh0Ycq0}GyNm*~~KczjfAC`8;epuQc`(fEG%GF-vj1ld*1(8oqX70&Czx8VRm4zI{EO| zOKw#sAFey?-q!LV^P_wi%g3oa%2y>H^;D%N>aR+FthcIqqdisG6YZ?Z&ffbq%VmFT zSMJ)C%ZJFzhv<T1#%ZlLPC0;a$_%&H3@)Oq}L_YcH(!!fG$9_QGl}toFicFRb>$YA>wz zrgCdwz!fG$9_QGl}toFi}y}kHW__j@4*Qj@e$n>A*etXHdiOq)&DIV%T^dvy#G!c%dcMl=BnbJU$)KPSfhD<`ErAbo(CP3 z_u744^@P0!6;J;0wEV%PKC6xxF{pU7-TC<=&(5sw-)eBN=lYlC(_VX~I()$3;?Rx* z@~zLxtJRf<6mPyYIDh?%>#F014Jl>~xHi9Y;Q7^iRvKDNJ>~2FvEpVo z<;!*WS+&cQp~Y@Z$K-9+zI5Csiw`RXOt>W6yB{2MsQMciw<}r?+O-y%ha3e7{Tcowxj~?y2aX4+fl{e{tNr zx`U&CCO>ytzW&C|vk}oh_r7;jzIL21@y`x-wap)0qj}aR`sb-0yXJ4~Hm|Nn^v|n* z**YJ*#AkIy^v~@}t(Ui&JhSe+=${LFw92bfo~fG^{WGG;;`!UhYd(~}z-q2#HCyMH{ra!BzM*obs@Q&)i zZF;wE8~wA+rK8Dn8tz9lrpmD+8TuaV@|?`&KbgymGM6u9E|1DwewDerD|7i+MxK-A zz|7@unadM0mp^1KugF}!k-0o1bNNZ;@|MiyGnvbCtURp+CZE;_)05T?)1TH9t2eDR zW=~p!%+9nnnf+q{rol=1?AI--{m>9OZfopQa(Vt zln>A@{nc9m*VB}I`f0%T^?wDQ-5%Iqxo6(xIEM1 zqIfZ&1UU?CElrN!Qc@*_3zrr5nU9?O281^eqi+alZ&C1nY zsSbI~hVw`dq7+{|)p1k%M`T z=VA1r7p5NSOXcHKPXCfT{Z4x5kJ3*+RlW3I*+ajUos0w7&p2@HqI?|nCiyCy^cW}o z#;IQ8WRG#O(-?i!=h|hQ+H0KrAU*iUIQh+(_EBH52R|F*59*^FKgoXlM{b~Uat0WA z)==po$AHn#8VXY{ISGvaSVLj#B!_{qpEVT5f8;!=e4NU$OY+z&J+wpm@u%vg-LeP& z%TD|!`-zupm!0iUFY@F(FnY*&VDyvoz|>3517i<44~(7UJg~(pp5ef>i<~Eww`(8YL(KVu znD;zCg}W%S0o&630kczgS18w=7Fc&(VBLX%bvFjqof%knX<*&4fpzx=jy};l(~^^a z%6n)()_cJ89-Mb-_=k7##(Hl^x!xzjdd~>!{UfaRlCa)a!g`Mh>-{FI_QI*pSiNG` zf2=(D(>VFrIQic=#l<+q%Q(f+IK|gE#oajd2jkRFj8p%y_n0cjHp#=%14}=wdSTfE z%T8GK!)h0-_QI+EgygI8u1JcVl_!51CqEk}{~M>c7^ip{r#Kp?_!_6U8>jwYocf8e zY`{*H!;*)k2bO+V^}@0TmYuNdht)1v?S<3*3hXh~y_$4yLFMK*Wc(e8#=HZAt^evi zMv^I&?1#1rlYYzo$4+U!v1#1rlYYzpJmvFbiv9&kJ7^i2AlTPDQmvOSeIN4^b{V)2p z|AkW-i9@w!xr=Tb+rnLR`h>ga z#?e>YMK_K<6uHxE7`8X$Eb$X1Ge&bZHak9sleLD5= zEc&PqPVF*I?KMt*kRCe+Lq7S<%4r|9>yf_C#C*_xN2DK5q-US&DwNa#nN^CcKPoIAnj=R69g zUe2lD)PIbL7w1}(6EDueVA{nwSSqJ~O5V=Fk{&w;gYld6<4@I#pJfmJmz~5#_Uqn0 zdcIE%BYF0Gl82S^z{+`GpUa6=PM+x*8+_iF)^uyT7t8!`z!vIq%&h&wDrN;k}#m^WIJM z^4?AM@ZL>!^4?AM^WIJE;yo#SgL)~a&%nsjmtgeJ$6)l+_h9O!Pr}$kUxl%gz71nP zeH%{gGN!$f#}Cqjf21G3sb1cb${zeIJMq8lCoU=1QrvB?k@~=Q?mJRGV}0QJ0z#xe&%r1%iJz|SR-Vo?uVdX_d{UH=^HTe^cfgE z^d%Vm^f8!v>3b$0?V(S?*hyc7v7bH+(=PfpOnX(1A0&@|qzAuAKmJs`_*wSgf7wY~ zWWVl*P#5n?6ff2k`GGY;{)z3fIRW|DF1sHBM?c#f0>^gQ+ycjT*_;FOu0-)-j#a#v zdlfI{WW|fQTJd5ISG;1oN_$u%WG8EZ>}QQ|{m{lTHXtuQphx~ezx+nM@+bDl&)6yd zW541;yA&_lt8)AxdHf?i_)Yrpr|QMevIqamPU50?G54u1=0w%ST&cR4Lsb`ZtLkFT zRb9-*s*5?gtSipxs*5>YK4eapZ;_YJ(WAbBe#MA-6+7%vOtDk3#(wny+NHk1oTzf< zO35>aN)L0Z^fTwGUgl!i!yGL;nbT!IbGmDn-TS3)ATK|lNB%*-{6@Xu&2gF_mPI-d8`w-LalryNDHO_Pr z6FB7$tg|-9(pH$b-~*Vr;2V>#V~jn~PGjt3 ztRRE^j3Jo*rgHkB_;2-J7Z>pDmE_?8^?8N_!A@nm|V%)#;y(HzXZy2Y(RQ`TN z>|=b3YH?4wt8vO{jbq<4d7hO#EO}V+aO_*<_n~6?TVl&|#42}ddg0dk!sP&k%MA*b zGZZeDC|r(FxZI;~IZ5Gi6)R8kp2??q!1Sbf!1Ski!0Ju&fZ3Dg0kbpB17?4kp9{C9 z7jCUDTnt4NQ_848z66fVaoT<%f0oTPBMij}8%&*am5XnN8-Y5LRrSx|49SIwR@ z-b%bcgcZ_ph=(=Xt( z{u$>Rs?bZhUhu;2c^CXWFaF`(H1os4Z^OU;x8e9L z_UDB;`F}`G?&Ae7{9bS2_j>=g-|H>t+fVjRZZ8wu9*6U;BIOmq?THqiyT%*?zq!3w zqn^7eUfi4Vtk_Ym*ujb&tbH!5{V%M2F|7SEtbH`B{WVP6$y;Fdq2x0#`%v;6So=Yk zeJFVm%s!NS$>h_SIm|wk{0i1SRORGjk|$4twV#Ex&xNU%eA498z8Kbi8CL9I?XO|l zOFjwX2l7c6|Bz3@_)YrpC;24h_?dhX#{aUDxX6CRi~i&Gqzli_qYv?k+Y9p^M|Og_E)fOXCTD_-<5aw+v0_Lk~1>^aqE*o#sx^6XL5 z*@E4Jp{U6dDG84se04ipZg8}U%m&y z4~iFY^sLxXuGqnf9jw^FoI9w`D0Y-9b};7`nyVE%m1}KM>?l|4VDxK^qh4Z1xnc)n zr`AgB*BVN@I2S^Oa{-let|9rT$Ih3K;e0{*Id@RK(H=XeLMGa2=T|W28nT~r4bC)F zuJ$6YH48mj%g`^sQLolM?9tf7POX*LuQgQhigC1aY@K~6ub^D{2CO^;R(=92Z-JH1 zz{+!AYr9`>Yrv$>Yrw3>YrwR>Yvsw)&lBsIbrT{ z#T;KrkIOA{mviPW7tQr<1)b!yvOlgt_AXE5X*`-dYXRlxNx8AEaA{s1elfR%5+%0pn~C$RDsSosXBJO@_(1N(JW>u-`@_`WRqM|m1PQT_%K z7y1LNc+pQhD|VDCcCcaxD|WDA2P<~4Vh1aBuws|Wl{?uxEv;ED*Rpp@TH{=9X78f3 zCc0eC-f3wKa=D+CYb+qIu|V#pv4DP!1($QuF6E+Tr^W((Ph)|0DQBR)D#s6!$3GfV z_)TLCf2v-^4*w{2uwn-*Ui?eFF`l;HqF$Kis24^b^}^Icy)ggs-!T6lIhf~o9!4Ma z!qh{3seIvgDA6a$pH+O4{A`^3Z;b!wC&>7CiDNw3uOPGVw{+ruEBaLXNWN(@j(yU; zA;MSqGWyH*bE!`nr@m^O`mpraH$*&}`n;7Zc9bi2uwn-*cCe2Z9M?X(>xB&aJL1c; z>=D!-*dxHy#U2612KERr-#)0gKZM1K}C}$kV{@5ICo!^qA_bp`tc!5z3lH`>|tL9Gw#^m z!8Y#V{tl*H?C(-}WBewP)sKLzFi!o%nAovLsPzZ?PR*Fuu}7fX=8(8Y zfKwY)zVN%S=#w-S%qMA#7~_BT2#O1Pgqojio}7>AGihuFSh0f@J6N%U6+4)5$G!|! z>|n(XR_s!_#V*O)H+^vG=cXt1f8#VRj2UXJz1M|Twr*j(_Wr}eN0XWwKXv*P= zAJpZ8?9)qbHa_a*H?uXK{hRT)?yqFix2hT+(DwQ4{>ASzZt~pY*=J22H17QAgV{&R zPcnY@>1sB*?h)gShTod4_V}Z<@&m5V;@F&zu`S#0-fZLN9x*##zH&k~vpUImmqC-W z760;}@lJ*MS(pAH6*%5F_}M6K4lv1P|QyOY6g) zv90|{a{_%BzWC*@0(}^M=e)UrJ`5i*;@dzUhIc!>NrgTP-*rUO3Vj%Ee^RpweHh-i zU-Jrm7{30l78Uw1+`4Yj3Vj%MKFP$fJjg$=`~$x-uW5xC!O!i|q(Y3~xhH-bh!NcB zpt*qZpOQu zaAD~B&A#(-Y*!(juyn%G2}>s|ov?pajBOg@o{|6Tp!;*)k2bO+VK5uA)%8`+6@Vg6`x5>BDTx$D4&8tqn5Jx?^<`d7+hWP#IFUvXE zagaQAim|8dT_2Jw=F~s3`A5c|Uj6#G4L_{$Wt+6GjyvuXD}Q0l8>%Bt{mgjYz0Xuv z_~r}amp_92G3);W7JXJ_W@&s@7Q*WS$eA#?u8oZsr4KkJ;I>zx1VTwGe8w#XTl7tyW{ z&pOMP_BKEEJY)Q@{qYwW!#(O zHYQ$IRbDO251I3iQhxQ9XB(qu%J$95{&4%Qiy2ezMTh*%7<)z?y0kHN-nzxljj?}^ zXKPHmTzP9JU+47HIsJ96-a2Pb=IqRz{qa1tY**&mn>jyZ&Oe#+Tb=V~o%3^@^M9R- zOKZkgT(b(=MI2#`FIeLX*7$-ozF>_nSmO)U_<}XQVB)oKTtAjafBwgeYacJ)XP9Rc zU*;dhop}k?JPB)_gf&mX^eg5)So0*Tc@n07GEb&*nC?4LGI!m)qaJPF7CY4fDYnI|RBJPD(Rc@joH^CV2Y%#$$oFi*m2Vnfn`~Yj7gf&mXjJt*Nb8X!Hr_9ejUNCW_ z&#+!7zN{lKac6yj=?|7tS7A?rQAj&jBw>s?LH4YuCFj5{~J zT63nauIYZGT$Hc)8DphnY=V8P8efrZ8jU<&4Kp8WWD2v!wCSU*8rM z@3*M&I#=8oezD898G1&Xbyqm``B}zGj=4MhVxO0dw_Nrf@`ti~`_0Cd@-L4bVT_*b zvn!3!ze|S;jH&mdRZcd>p3U~^V2qus&e_`-`)6ITt1;~wbM(%}y)GVDmUrLa@>0In zQhiH3lMcM3)W6(X7nb$@>B93%d!`RNFUZal{(Nqb{kt!DZrLu%)n4S~2lU84=$GH9 zSN_Bv`58Oqf9zLWe7wZ$DHJ6+2k5 zgB3eiv4a&mSh0f@J6N%^@)SE*v4a&mSh0f@J6N%U6+4v^JINC}Sh0f@J6N%U6+2k5 zv+@)>*vE@`gz?CDaU9Qhe`#wv<&NX`Jx`~xT+8iwmbGl*T=)IwI=^1HIq(O`G1z0) z=HA-gS@Bw!6V~GOeR4vdSO3s^vHzFzF`d!HF&lK=1?wCM))^G6vng0-RpV4X+7 zI{$$i^DNq*NBOzP&sVU{!F1k*o&J3C$9m_&e9OCO>{)ciE)M9%Jy;Fl5>zyNYxjEtAe#hbFqVoL(I^F#6Z@p{aSvQ~jXz$mQ|6q^u zRap5dtb7$#z6vW}g_Wd&y&L0Ib}taTICdJ3yQn@oCN3^(Sx zQO!}*tF;f-`~z$Lfq#g1`dZ`AuQd+V9UfSBcwpV(fpv!m)*T*`AH4AX6@K_3?q9k7 zpSy99yRneFv5>p5kh`&vyRk6edt}!qf3$lYZY<3AUS4@%^lhWwO>*6YZf+Z z&4RUN!CJFmty!?vELdw6tThYPngwgkQu)F&mVf_@MdK^3x#hhD&(XK@twDbO(r{nn z&u5fpx;@c+d8sQ8ey=2Zh^Zg%VsZn?z+HyFn(sPhVzJnHAC(->eyXuNbLGYdpEWWp zcIdQ%a?iA5)c#9YIegEtGfd}{k8iG?^YGt|mwfla>IFmJG>+e^RKI-cJ>&Y3D^%OH z{@D2E;~p6I(umo{tF~xAZvW$&n9dI-Ju>!~r(4wO-TSe7AM3tuCE5^v^S3W5XYX6% zu{(WPIdZWYzx33Xl}WwVF`2ge&91b4Yi;ArADdm-XyqDD+I&vs^o`cC@^8+YQ#p5? zHI4r;VNNA1xrXtJZ_TM}@{iSw&-!#uCAB?xc5M%E@+aqK)#QiZ{1BWUqD<+B;QSDr zAA<8kaDE5}M?a{p&o>-M>@s}fdG#{~hZvVYIq`}S|{VtcRyJ4m|Wx6FMg=l_L9z4{^xZj7V93^ z#kkv16N@8Wt?|?=CKjuAJJQPO|3f==HU4{#b&5UyzE{cTKfRps^tXOqoW1!kj0c_j zZT^0{m5fhc@wNQE?SE-};t3DuSLACLzrWYr`Nd<_HC}Iv(Ruh_L*q4jjL6?|NPH88&mJh{dP0Pp1sf6!+2!$)r>xK%ki$U-|W(f#UWEa zvGS#&ABK+o%=m#5A1YQl^9$p{u6VHMI`>QC56^g@`2Bu!j6ZHYp}73CuZ(*PyRW#r z&)3EW{bhV{@M{08E6puAebRI4xB2S3P7IsfHpHGCx5`6dx1V2Y{JYH`2%Bv@-1w|3 z?+YKiKGJyd;YGM^#hZNnQ*XtYiT|;iGm2Y}`*zu9uji0^g=Fn}EJB-Ji z*t_IoUhfoUY&O}-$B*e8hTlBN_@YI+hD&yTz_`zg-NW!r#~XjU)Sts!J*&o@d-e>! z-RWNA*Jqv?PP^$Y{c23V6@RkjhQ+h(YW@GNCpRoM|3$5z|8d~P#g_Ng`uXc;Z&u9u!%?R5 z;ghx~wjSHfc-#HADOUKXyK#p(m13z`M;q_F&CbOMBabmY;I-Y0t5!bN_=);`iY2zM z@h(H!mgNWS)V`F@&h1?4Y4_{yrT!_49$(fw_Nx<1d-j~!qqOs_F{hOFk7{#j*)GaY z8c~}EkUxHI2eSt~_a5Ee82!gKKg^hV`%OO77<&djd5AG~{&s~LWB-!Z|H;Z}*O0%| znD(k1KS&<`NDqFKe*CF=@w4o~|FV;~$bRDW^~l-QmngrtRc%Zme}A`mwZ0eith`H8 zvkm=+-`dQWdbfM4xiR)^^F|9}>>M_15o7FsXqiQgY1fup*O>OI96v}N|40vhlYacE zdhxUD!T++8xX6CurFK!iUF*-SEy!>E=Euh9d1&GX#^~ST(|;IK?ZvC>hr1dLv>sRL1 zugtAqnOnayw|-@A{mR_>mAUoH>LRxx*V^Z#S`I9JX5tDJcv6oU#gY%NY25ph7mHH{ z)cC~yQ;S``U87ch^0P&YC2IV{_$Q0?i`A@r<%=g5PpU-GdARt? zHY*#S`ohHG!^KuKj_>^HRToTNiVbJ&w4>#yV)8&Z_PyX)xuRQhGq>huZq3cynwz;b zH*;%l=GNS7sei7ynOk!+x8`PU&CT4Jo4GYNb8Bwq*4)gkxtUvYGq>huZq2p2(wdvO zH8*o>Zsyk9%&obZTXQqF=4Niq&D@%sxi#1NjK=uazv-EEfATns(aH~=nteO_7~{$v zXJ^m-=4j(?@BKBK@Yim}V-D?`-QVIU<3CIql=Z&%NaOvc-k9xtQy1g6H;vyRzTVk5 z>pCG@ziW+SZk4s#uEs0f_i9<*efImM{Jg!tD)pSZdGk=}@4R?Wy(eA0WRN{S%a;kV z^Ns754YGg3U6%`L7v(S9@Mp6J`4-(zG)7OWRwo7WW z=eX*r#@K(`mZurht_kgGOnX(1A0&@|qzAuAKmJs`_*wSgf7wY~WIyp*h1Ssjj`vhGjF$Y?A-PB8e{*CtKVVev}^JfHKx5P#}AUnKhlHWq#u8(Ui>V3@W1RN zF0!9^-TZEUtC#Z6zU^m>eEU^vjGn2x^tE#IKi{j5G4*DzUTTazD;`v1?CkYvZ!5?C zi|(m0?P_v;jcKpS@q^^?kM!WTQh)TP>c!8p2mi}X;v)Nrm)b>n$0?VYJ;;A~@8!nm zIs4K9HT$FfbN+CJG4-zcd5y7WyVI|Ir`tniE?2jBr5xVmQ*LkZN;$vj zPkRB2SK1?(J=@gwAQrE*r!f1|Uc=gz_8`_?mAgHQ`A2%(9>@HtdWo0paeF0;i|luM zD=SYqyu~Z!_7<;{^PB#(7qEDxJ%ZVj_6`=Ww5Krp(_X{cmG&UkUX{B&i}^=-+#bjL zse0X>$owxm{T^yTdkvSL>ohn~NUU@96 z{24|kc{QxO7gjzDD^G@%Kf}ta;od3VhLwj~dCJdWbVC*5Mg0Yia3&wtO zFqn3co58eK<@iDJ_(yv1Td6Ya&j9Od2${YJ>)_#@ghfp zsh8Xd#vXDi7(2;AA*X_|lUxhNesVCFc9EOGv{&W$LGt)VdhlDRKl)Sk z;%C`||79m}k^RcesEcxP8yIG5-cRj+XkS}{?p$n*%FXxp4cosxr!sxj zH7iT4)i1pIz?{mNtFKkL`iy>|`vr3<-?m)4a`V&u!lgTe|YwQFDv&Sv2Nvp;r+wgExxSq zuBzS0{`S67%zLX#+pSwU==%O)u_x~g%Wbi4<Q^)`DK zc5mDMfp=j~F27D?=}r5G8CQ%6q1W1#W4`VePX5Eq;eyxJs@yT5U)XQ6(e{4rg>(7^ z-mm?(>zb9XLccKa^iiSt;58~cf7UlV_R+|2(nG6PJ{#3HJU?Wly|cq7tmCqc_o{lo z<{6tMlis_PXHDL>dJpK|lZqSmB_9`T(6g|AcL}?g=KdXuKSyfFI`i@8PVPJ^cjdV+ z=dA2Ucqe6Nbd7y3=kvP6cGoqIotzvp&O3USUATAIg?pDBWy*Kig?pD>xOdrwdzW3f zciDx1m+k8MA>W(NcNWTdDd(a;wYkgp{~!9@y&u;es{>QpQV($pjeUip} z516}mf4=SW+2Cd1|AhN3&gS{v8~XB}@Vn03z2CGL>Ak1(zkdg6Yjk7X;c>Qk8>|mE z)_d56=a6<6;y>ja(w`gWE_S&)cg+{xY5B?DX|Xt_J7Wvq*VOKe{p8=*=#HOz*Jk5R zM)gbD4hK!E^7$%pTp@bMMj2e%*m4`t>a3VwLM&6Xl6*Uy$y~TCOhsq3`hcvl`E?-rU_C%H7?e z+}$0@-QA(w-5tu^-Jx7}hwy{P}jn<`k($;z22=beiy`w zBQkpD0_&X%tamQ3-nqbf=K|}U3#@l8u->`AdglV`oeQjYF0kIYz`PUr|NTA;V{PF( z&Huc2nz~1)*wLRoGwyWnj&Y~^c#J#U(_`G}{vPA5yw{iBO{0@>r+a{mJKYat+%3E} zSevi@Z|)6h+;M+Z>z(dS5HH=SAYQs_LA-PagLsv9Gh)1SXM=d@E(h__9S`EQ@a{+L zo&NvJ-4ES2W~_Y|GwyUhS#e|>DUPt>2rG^->)pcp)wT8ghq_<=>Ba3s-v>Sq-EJEm zvOQ|N{Z2Q8rhN{x^7UT7E-Z3zJL73rUK?({`w-(!-LDCE+bn1=0mj&HOq(l=vF*LrYK+YnYmUwcu>y?5_c%1|zO%I6)^y;7Nee2C>i zeE<7bheKldw;Nty<>GY)o)vCAx_jk{{L0{Y%d>x1%6o1(ZS7L0=fC~sldOBRf6lQ@ zgJw%4E;{JgiQ(?fd(G@{0HFlS|(7Yn$}TrPK3{9p21k8+^#I z-78O?&>`Tfqhl;)?y;G%%JHYlJrfI+6C=q}E~dOk<;ePeaon|dq8f%x?^4egoHk&5 z*kt`0Z?owGVf1f1TlsOlCWgV^9$|d-xsQZ?mvuB=YK6(+fiF53ud=}t;qa~68}Bss z$uPccJL4{6p9%xFJJfiM#hwn&taXTSo3)+}zgc|a|H1Ub4Gvw#%5UmcUo!Hsyn>yc zk%@Y&oM*+z#JWoP+m>x--13>HLi>*oGv48?Cqs{WI~Z@;{fTh?!5xj4KWcK=dFU`u60+8$D4i zqMuDB`niaHHjaKSqMwbUpNr^c$hc&MC#t>mFhJc8_O^^CosOe&e>MibXc)V%+(-$BQL)J+dbM=p#k1 zmAV?AGWDTiud8bOk6Z39wtuk3j9JIQ$prUoa5{slD>xg1vn@EAgKJB0ZM1l$wwtfS z1I}(&54Yc8TKHgcd*h*tP7RBHdbsiM7E{97ZysUXYL92auP*Owyv~PDgqa_9G5(@mp-W@dweLvF*nAIkw#x|Hrl) z6PMWbntY5`Y`ZaWjBPh2zVwaM-s0ewyH&a^-n@=jxV#G)EARWtOGWRi+8G~z+DpZx zZ`&K6x8I9J`!*eompp!Y@nwfj#vi}*e6i;aU5rm2`D}6VOGg?{j`Qunb&oP0e8*$O zek<1MJ!-8<#iOHZ{KWwitX^`zsf)f+JaJn)%LA9b_T}R4jXM}uj(w?k;i8Vl@1OEQ zalqJ4#wR>JwdgXsi}C1FpDP~QudDF|S3FfLHu@;ze%nkgZXe#wxXqc9imNKMJhNx7 z3B~BTZj~c0pI3Ky>q*7nIY%0ww%k)iv%|Voc6;WqtnJ>DiYI$?vhw9tnp%urv8$DD zu$NpeUe~A6Wn0^xdUr!wIe~gzg@rpjLCyw|$#@EV;Z;X+Z z6Qk(=dg6%xV}CFi`a_Jh$q?%pFOwl&v2R#8eIv%#%8766561Kd?|<(TSI!>C>}O6` zP`QhHnEp!5&)XgGQn>EC4(9VkX1@@wm{*I-`y-}>!?*2h<+IP35-#1e7Sn64dpayO zp{tcIw$9^Wz`M1$ufFla;WyXR`a|#6CIr{7!pJXczHN5l%c18zHJ`U%=B4oV?~gE> z+mD(a-XGT4_|DGHhi=y%X?%BwXTpRXYVo~!?BijFlWTE*y#K@DvftF&yYUJ!pZ}+y zgNsXWz6~yp!NnptKL;20;9?qFT!QNZ!NoDSxLe!P_?piT(I*vGUPgKoL=DpzN!{Fx0;O5WZ=GEZl+u-Km;O1w)Uk+}53vS*EZaxfdo(yjO3~pWxZoUm} z9u97P#{ZQx?ueIh9C!G?}YafkmaY248tOeT&yVr?>U+z~I6iQ|sG zVdZh$5nn5hog6E9|t+6Jd0dE|pLF%nJRsemeB% z+^N#z^7w4^*>K(i9V@#HoE28PXG-X>#^IH&gJ*@lTTKm%{Iz{$+R#~{vg@>P%vbFy zS6n?S{{4?>VftBzR))viwe=y>t)I&$KBw*c$VQcOwtOL6I(vG!d(bkKJGXu@)O|8N zxI7jvbIvGJFPZpky`F85mzMH=E@G@HMt;uxN7wH48^*JvF~85}8?!(3+=Xq*?HBp9 zUH#DLw-$4!g;UPxP=Df(S>eW8riQgY?pXikm9xTHy{3dd>vgU_vHz^F|FzGAIdRX} z^O9L%!;PN|e~CHaiM?ip>T8dNl|DYI{+$@#X@8p-&Yjq;{(zpd!p6r<2w$$>y}meM zR+w?zc)wm0b7I?P#vot}>^ie+{ggQNXP^FPvCa8M*54P${-|}HC^nndx&F&I_BU_+ zba6$;PW5NRv46$*XN#T3cdXwhj{SkvDaF)P4zE8Uj{Ubke%8$oJga$wJ#0n$U&gp+ zpWlkzoNVXDIz#4J$+)%Y2j4q*n@4}rt}-mn18YYgK5}}8%1Ln^SnbxS#kwDLth^oP zfvwMvyj_9Or?vdW^TYBwvNboPYe>!g$g7=Z|%M>&^z}TWj2T z3+3up^UaNZtogG$-xhy%>eprBuC_PkSuXWzE&eIw2HtPppRR8->KQEcY7YM?%%2N- z&*l4-Ka+R;iZQN!%Xy&s+XCmz#+-kAyS&Z5Esgnp!S9_NbH-@rUF1cM{odS{2l`KA zod;5v_LV>MzJ391Z`5-k*Irw{bPn0b=bwJhUizOtthoC=;Mm5aY)0On#W_|veW}zL z{clV^Y|OK6zZY)Ivk2FA^PBwR&MSWK^JLd{<^lP?QQvoX8yqv|l=e90J(1;9yhnC< zb#VE1`A&zvr1v}UcggVH+2!q}e#%|0K3`ql2FDA`^CiQ(EoaXH_Xv`2_zu_E&l*>+ zy?}Hk{k9IK_G%x2{pI;X)NeBQ(6g8EIiY0miPqVM`rSUIltJD-yTJX9WKw%&|9tx( zFXQaQpWi93a(v=!D>`NED|xr3fju(ZWXka+Q_fuum3!vy2j#D=e?jofT@lKAjJq;; zX8$hv`T196z1&MtUDy-%<95f!vzKYelBYcG@$DXtWU#X#dzpXog6tet=Vknz8MRmK zqV2Gk5qqCBWG|z-B!m48*~^H1EE=+xk*_2}+#9l&5&J&SkiASiGqHP0lJR{>>}AC2 zhrUmWy^QLTyzjR#ccRpnxT6K5N98bgs3hZ=J6DwBbI;t-qMZ18=1!O7J*!^qfn_tS zSV)Gt8nTxWd;JaB%cw6&2AdnQml6ARHDoWNx+H`B4cW_xy+0eWmyxd|Q;TmcE@Ceu z_Hk^;UPgUMGQK~Ey^PrRpN8yZRF`BL_DRaUj97g@eJ1v+`X_|;@*(GjM(>q zhU{fxU)9;Z^#}Tx}Dcgx`gmA@LgRA!FY>3$G7DnWt9E()Ggo+}(rc+@DwiEx zpTS!$dr$EE$-B!|Bm=L}<`I)WV4q)B{(jiQ#;>mb%gU%TCmG*;`>OnXKjU-WU!}6< z2M-x<^ZLq_Z+>6nj|Qz&nf}m&R(`{;R;-NgSmVE+@{7vo^=f?l*ySt7Emvde6=R!Z zZg}(7OwX?I`n8#Kwk$5sRM)5%F34oVluiGV$+o(SyJfQZi#CU4YD@Qr4$RcX7M1cT3(>lIv<=8ghp&DcJO-*Y4 zr!Dfc{7+nHyJYZ*p2b(vi4Rp5zLgF5T(%Jl*-VVo7GkG164Sw7J!W>Ud&N!R*rg{M z-_&wM_~Y+uJa)+S;l!J2yx0-fgby})++=P%b!d3>@f!c`i$P(n3!bp@J>DM}{&2vP z#(DRcgZ}0z<898qBE)Yujo;h+im=-kHKx49v(J?Bzq$5VWAt3~r{|2(-}&nrQ}1hM zOtEt8Y4K`}v2*51&s#b6kKMS&v`gjJt$s@>-@ni8rJfxh{@XwG-+oV7@A6xY3$kZk zB`@vlGrlP8Uv_kT*{%+A>dW?0EHLx1VdSg-tyJ@P+xDlXWsc%AXo;uV!| z*K)CnWaI`3F6U7y1=1>Q%h3NAbc=#RdBnFWRN@d_c=mev3VqEcIOS&QhiRO1ot$s`s<2 ze_oM2@7=I$MRxwC({dH{w@+VKuA+W8xasm0^-szbFXZJP^vG}Mmp`dje#Rd8A3GHn z>{q<5ZPmPtwB5>Oz!kbCjC3y_e`dGFTUg9O!iE_=)O#L4!&SqCj0xo za5ujpVf}yqp?76!FXi$B^70RQZ%^r#TXmn@0A+cnpHW%7@OiIO;y3BUpQ;N#%Le=}+lY&7CSGa_aim`5OWp=CZI=wZ<+59s@}pbV7(LJ3QDgKk z*5h|3L%sW)y^S&U40@!sF?PPWb7pM);oV?NyH*;#tugJr@|5k3@dG}=PWc3uPhj~3 zmQP^$1eQ-=`2?0v;P3JY<>~{l`T(pxV9%yL0ILtc>I1O)0IWU$(+AW>`nlQ;%O}?7 zldpJIK18Q{OI`9gHYgVKPsPake2N`yQA}xL@4xS2erDd=Vu?1!%!i+yS!3qOu-&d! z&iwh?op&>4UVZoc-y1XE4*qI)W9H#cuiVp^`MLWa{$O02&-XTFK7V`qK4p3Pe*2a3 zV>dp)7(GW_cc3x)*LdR~W9n`7PFrK_Ic(Iy#@M;~YJW1u{)cy|G3`=0^P%LKC#8q^ zQ~H@#RWI|c>|q|3oy^a&zc!!O+QodX_EIiCATR%*M}9-U{7Jp?Gxo^;*r~W+zv4w6 zsB-c{$&)uq5Ba3@lV_@4@=w`AUMf4uZ)JZizpb^4{8sIyTz)`a{y~rYhJN{zdgW*A zk^iw%alwAYi*~7;{7~}bjnYFtS?Z5@rs^gCls)97vXgvO_Sf>;TD!<^)n3Zw2jt}+ z^vG}MFZ~(om7lRk{>M(m1^X2*@<5f7A4;CQQF_QHrJp=g^^$+e9`aJzNxmxkYx!-h zUF5fFFXi$B^70RQZHwCvTJ<@=56@&s4qSpR$L% zRCbcD%Kln@TWc5jt=dbu{D8dtgC6+}{qiUE%Foy%|6`}(g8j^mIz!Mr$r>%znurX{ z-V1d7C{l%)HIs8D`$r`3Cihu}w0p zWqOu1PC8lpR2OTaY+$XFZLFcPnYC4IVa-(=S&Lbxum@(Hf{_^&*D081S*KuhvQEL& z#X1FJ1M3uwZLCu;Hj`t(w54GzD5vd`!6$kaUr8rER9*O1HsEvFMl57AF;ZKIo!UrD z+3!%V&J$q9HTgEocqb2snFq+v;Tz-pK;8~BZ;;Q!%qQgeF!K!i9a#Hrn0bl)j>_5Z zNS^%;j2`woF#6f=z|_lr2gV-uJ1};#uYs|j{SK`21ekeP^32cD!@OPUkMp_eWuBKk z%>S~JbwT#)oCN)>BWf?@@&oen4|?P`^q2mO^~%rKBmZM3`yJV@cljf8Sm1= zJRtqd52}}WL-sJA$WG=N*{^*!`k9y1UdrVMQep*ljkr$!{k5A+c0?%^SQ~#e2IA;CXZtNhsm#47hv)()(cp98cd$X z`l52y9m%sE!RTR~g3-_V1(T<-uEE&DdIw`C>mZE%tdAz2@=ut&RPyAj(nB6A{p7c* zm%LZ@kPpjF@@mrD?ek8{EwZikFsC!QvOLf^NHk{ zXQYSuNBWtUR4?|q|0oy>=_UwIn(nGe-o%H;>-(y@qjd!RT3@JF>kjs4J;F|{U)Znpi*~7; z`B3uAGt$HSBmK-vs+ajn_ArmhPUbh+Uz-nW?P5MudnuP6ke7eZBfp_v{-j>{8GGb^ z>{MK^-=EtwJkO!ekV7he7IXds>ph*AGf7zIfs#j0!`xf-Qm%T%=z(>PDyCjo@5|u- z*0}g_1k-knDVW$1Q<#_%YnWKm2VnXDeFLU%&}U%!41EcvFVV+f^*wmuJBym%m@DK@ z<_h_lxkCPDu3${zH|7c-FCRyZyZ?sy@V|Ba^7#f#OqF}UtZ}S;Fl!%cBFvh|S_!jO zvWCK}p{%ViYb$Fm%$mzu3~P;s7oL69{6Q0&O}6g&98X@5-)rhVLh z(|HK((zt^)uhK@1JMv78JMv78JMv7ecjTE`@5nQ?-jQc&y{qM!wRa*5-=)^pJMv8V zlRQ&?CeM`r$ukufa!4O9t#^tY;|>{~g?Sd8FgmFVrY`OGu|ekmKb3Px?eG5E&W*J% zpk3N8z}iQUXKH^zo~eBYd8YOwfPc zj67!)FnTzue83>G>oQ=TPPwZgD4kibaJo%gSkk?5+`JU<}50pKe zxyeq>;$*+xWuU(??+_|>j3dPkrj0spp^Z9+p^ZA9p^ZAXp^ZAvp^ZA{p^ZBKQ5(_U znD1*?$93NI-}HWsc4^$f8h5l&ZR?f7goKn>V;J=ta@S93#(pO_ibR#uJsLw-3x7m z?^zfljeXxn-_+3d#{7=Pzq8O?pvJh@HSQ{Phjl+yV`HeM=9`UO#@Bu*^Y^RpFanT|BI|^R78OWY@V_yOI5k`}}%FcF%UXar`%n|7{%q zKXS(LIi4?gHtMU3dX4S3*+wp_@~X)oYyWF-~@d)Gq8drXKv5%4x4L_25U!sRuv8$#2H7Ui)v# z`Tw$q=VT}PWWSG>c;L2A#ph~qge4D44=nw#>V;(wEIVP@52rW=IK|Nze^XzQCyvJQ z8|CsREI-33ju{-Ev$()fpT!G~?JB6xl~ zpuSX29F3D7jFW$)-`azG@~4$2KN~0i8>hIK{Vra4DzA%r%zxAeyLja;Ub%}`?&6iZ zc;zl$xr-O&iWl;V7kaEd>UHs=UaK$JWA!CF6|eup-g`i6QKZ}7BW49LXBl%s%!yNV z4rVduFy@E>bDBYPL`4t-W<^0oMY4z}0&kTE6;LFa#WCj`#~iD2b;a)L-MhO`e(x{)_on{xbkrBeK|I<4$Kmn7(qDdD#z=p8Inn-JezNqJ z*O%#4JCLQnyxo|;^q03Y)1|+>Us!(aFK3&xO)+5qE!f8Z*pCIS`YwUJY+x@lxazwM zuKJGbW3`HBn}WTqz&_@|-nL+GbFlXXxavEc^VxURIn&c|&h&VkuRI@el|R|XOv$H= zC9sb%u#Y{koHMRbC4GtGA^!rTr+al^Tx#o zFZ=`fvjO8`ms85M??>CO^r=JM<8co3koiE-zvN}1Pr@R8X1sKRsIJ1MSvec^=( zI&@{0r|z65W0xh@B=52J6LIRp>yQuWJTbod`~l=wnm-sj4%wN!^za<(^Va0!vb`J7 ze{=F0w~USl?%0mJ#eAdVRh!q7&loo<_S-&?j~F{Db~~gk`L7F(juThhgnaY&W8(XZ zmE$fos22P8S&QlK{wc+|Tel_;-YCc8Rw?Bi9`B0}Ub+U;&pEWwzGYVU$j!&bHoXh? zU-$la-FJoOzWt#%re_<*w;VVnHf&gq)$7}b;(41M#`OND*#49~jw1JYd0gE5(c?<` z#F25{MK31r(%IgRTKatQ&NGI@%O-Rt&lLv6SDrnC{Ln4~V~6!mBX@meKs@6Qr;xw9 ze?Xl7n-j@rS^Bz*o^l<8L- ze@9&LPlu2{J8M|He4)b6_q{Wov|ZuX&m10~8(nylL+*-Q4k^E#bP#|$@J^q zxH^7$e<{O-rlk(32fbpyvwM(NpL%^L_GX6rQAMs4@INPMcFa5nw zTydciv*x%PCs*L5n#+PHC0ym_8dwzH=8iCuGl=6U#~H^i1t z3?#SSrdNFOmBHj;_jZk~JJ-l(|9Ecve22TpcW(68_`@e9=G8%G#upwR!1ODIcZx5! zFL|DMey8~QGPg6m)r*~CpQTHCo;>8t*dpG>^b0mVD^5J%R`PAvo*VbS^5&9WJ1=$` zdlR|Y;Pd01M;3lyVAr_LE`@Ko_k#HCS%vqU&@GPopzszKbdQ^uhK+ODo!ed*-}$2O zvb$dz2OM0=u-&0o#vR9$GVim&dGX?g%=p>&JST2$9(Mfp+KtYPn+zFCUhd_cgTG+$S!# zYvJS9|5NOHd*QWK-#?yGUw%8P%K@=|THy_!Ixuc|_6X)P;j9jE%=M*g7yk9c_~hVH z{w)sOE-rG(RK~3E?3S_RE7Qo|ZrczqSnE;plXtg_XYBecd7BSf#;JKadAF4ph~ple zNdDxy=5gO$CXm0pqIqmJVjOwbC0oSjFD~uYYpw<2LAO1?^dEL=89#sje)7sYEEJ#G zt?+Z#EfrtAqmk)9ZoX_hx~}l8o3)DTw=R7DhRer^hZOF<+=_9@=L;YE@=CGKb*1k< zop+UZ#%3kY(^p+JzByMp?q=(>iO-FBi21+w@`iDZj+4o4pPx6bvBlrWTm3M5oVLbu zlN~Sllq1$R-QpV+zUJ7zVee~7doH)vEn(a5 zO8)f=+!l6wZ4zS^Kk4?ccFV%M9x*U%bm}8aAART0@W79yJ?CGvF+BCd!%Y9^#&MzZ z*upRLdN};`>B8UcH93r3x5O{~#I&%?^un{h^jKJ7aLIGRLr;XQjw;7m@%*R4U7MBi z+%wn9;nHJDnO`{h{jh1@r+KVfF6bGSS@KnK>qE~A^_Lbt=J?~n$6pq{X5U5Xu6+7+ z#vHKB$#px7E^XE2(u?bEd*(@|-_`E&x}jT^{HG1OuI~L&Wz1Z&+%0t%jVNQR&-p{^ z{`zHUtKt2})Sc9+@VWO+uB%_S@WfN*4U5kxbMS-_i-xVI6<+L&Wy25im6$zFTq(TO zz3`M?YlI0~m;9UGuy!~)l;f^?_IjcBJY_tOe0zhi#>a)P+JEyfqT@3x^Lcmg5#F8m z1@iKpwracVE2WOcW1Ow-HLtt1N%A&1=aB7F_ruHhId$TuX~wuGn9qmnt)F(;x*Ti8 zJJw1gr@ z(5d&csrl!nYrm&h)^v692$)gVUMolzfK#&_Cr7g};gY(n}r7u~u${-fo=wW@+xb~&pTHJ6;>iBgj|KexdoW{*j#$$Yc(W-B=gns?`LqfP=IgF4yv* z_g9v-+Hv^>^Pg{dobh&z$bOBmYe)8Lhg~bPUn}hzn*AEO{*oQ@VvmgBZ{uNy=H3&^ zwQt!M56H`Zdl%D(@4sJO<;&sZX<^^I{%M6rguU|-)wOTm-S^D5?_ARNTygjO`8|a{ zI%4}g@`G}XTVU??`QYK@div(@ZE}|r%CTOYvUNUok8&;k_<*hRK?mQZ^c4gPX={&+^obGiLH=c^vNmHC{u`I&jKK4smt zQNK?4#LLQBsKW)Fa_(E!X=C3uexQ`?q`#b*f4Fu4fBV|zo%1oL4yiiTH;laY zr|0Dj<|%D!YslPv-OEmwog4-7Y52`TdP~ z#sxjdr<~mKd@EkY^soMYRX(EC<>XE+uFfB?eFb^&F<0lEw=VYre|_}o zd}fQX&TrW3ntbHn3Lm-O_4$g8u4nvnyY|T&om=|C?kTe0Q`o&m_Ir)~6Gvvhx3YV# z?Dt%Ab*<&r6OLv+TYPzUp7-yElTRK!Ja7EUA>{g1@64T7DtydWcjR*`j^7T=`}Qm8 zU#~ng?|Xv#h&=hk z3&?hlnf)Hq?me^Ld)mEr_Iqu+2hV;Fe(=MOj4 z+^BrhW}A|C9WyFl8tTX`pC6UC-8hoRZ8bW#TDO7x&WEG(gch5T*Scg(9=Xfroj^_!9h{kQ-*^?odG`_*D()1b0zP^L{~ z*QQLD%dX3rewAIndhw#axrD6DB4$t*&fZ8%w06G7muHoXG|~8bUr$8 zYVP&c4ve38&6Ir4s=JX7nP*B~`{;ehj|`feU#LHXJnp+mx%aqp$&1XGl>c%-cXG>S zlkEe~G37kTN~ zpUV49?MpuK@l*3s z8+WoJQl2`6IHMhC`n6^mY{N|~7o6*zA2Y)y=tMI;8jMJT3P*W_j|R z+fL7qZL$gZhW3x9l0iX|w6HWYcN0 z>9l0iX|w6HWYcN0>9l0iX|w6HWYcN0>9l0iX|w6HWYcN0>9pkP+{p4&=S*^SjUZRo z4zlUA*>qa6>9pB&TC(Z1*>qa6>9pB&TC(Z1*>qa6>9pB&TC(Z1*>qa6>9pB&TC(Z1 z*>qa6>9pB&TC(Z1*>qa6>9pB&TC(Z1*>qa6>9qEZ`@*KvX47ezZaQr?otA7mZ8n{j zY&vZ=ot9i(D@%O2hLWo_LrE`d39{+5*>qa6>9pB&TC(Z1*>qa6>9pB&TC(Z1*>qa6 z>9pB&TC(Z1*>qa6>9pB&TC(Z1*>qa6>9pB&TC(Z1*>qa6>9pB&TC(Z1*>qa6>9pB& zTC(Z1*>qa6>9pB&TC(Z1*>qa6>9pB&T5`2^B3ElFa9pB&TC(Z1*>qa6 z>9pB&TC(Z1*>qa6>9pB&TC(Z1*>qa6>9pB&TC(Z1*>qa6>9pB&TJo3=dS%mT$)?k0 z(`m`3(`M6Y$)?k0(`m`3(`M6Y$)?k0(`m`3(`M6Y$)?k0(`m`3(`M6Y$<u`$IxX3B+H5*4*>u`$IxX3B+H5*4*>u`$IxX3B+H5*4 z*>u`$IxX3B+H5*4xw^L^SNB}x>K>C^-FuQvr_H9*l1-=0rqhy5r_H9*l1-=0rqhy5 zr_H9*l1-=0rqhy5r_H9*l1-=0rqhy5r_H9*l1-=0rqhy5r_H9*l1-=0rqhy5r?uOx z!lu(^(`lJ*I&C(cmTWq0Hl3DiI&C(cmTWq0Hl3DS-D{JpdvJ24Igl$Yf^0f%Hl3Di zI&C(cmTWq0Hl3DiI&C(cmTWq0Hl3DiI&C(cmTWq0Hl3DiI&C(cmTWq0Hl3DiI&C(c zmTWq0Hl3DiI&C(cmTWq0Hl3DiI&C(cmTWq0Hl3DiI&C(cmTWq0Hl3DiI&C(cmRxBs z9jS|Y00M3)=Z}*n@(FZotA7mZ8DvfY&vZ+otA7mZ8DvfY&vZ+otA7m zZ8DvfY&vZ+otA7mZ8DvfY&vZ+otA7mZ8DvfY&vZ+ot9i_v(C_L$(2S;uC!~i>9oOg zTC(Z1!E{=(>9oOgTC(Z1!E{=(>9oOgTC(Z1!E{=(>9oOgTC(Z1!E{=(>9lpG(~?c6 ztuvjLY&vb7>9l0iY3od9oOgTC(Z1!E{=(>9oOgTC(Z1!E{=(>9oOg zTC(Z1!E{=(>9oOgTC(Z1!E{=(>9oOgTC(Z1!E{=(>9oOgTC(Z1!E{=(>9oOgTC(Z1 z!E{=(>9oOgTC(Z1!E{=(>9oOgT5|R5hFm?SI;!b z)w52r>9o;wTC(Z1(R5m}>9o;wTC(Z1(R5m}>9o;wTC(Z1(R5m}>9o;wTC(Z1(R5m} z>9o;wTC(Z1(R5m}>9o;wTC(Z1(R5m}>9o;wTC(Z1(R5m}>9o;wTC(Z1(R5m}>9o;w zTC(Z1(R5mJ^=y}1J@X}3&$!9evv0ELw9#~0vgx$ZbXv0Mw9#~0vgx$ZbXv0Mw9#~0 zvgx$ZbXv0Mw9#~0vgx$ZbXv0Mw9#~0vgx$ZbXv0Mw9#~0vgx$ZbXv0Mw9yt2WYcM* z>9l0iX`|`1WYcM*>9l0iX`|`1WYcM*>9pkPSwGpe(=y$3+Gsj0*>u`yIxX3B+Gsj0 z*>u`yIxX3B+Gsj0%VRoiG@X`gI&CzamTWq0G@X`gI&CzamTWq0G@X`gI&CzamTWq0 zG@X`g8Wg;OJXYl)Bv<}Pa^*85n@$@|rzM+C8%?Jrn@$@|r!6tZPm8A0l1-u`yIxX3B+Gsj0*>u`yIxX3B+Gsj0*>u`yIxX3B+Gsj0HCWSWqv^C{(`lpWv}2$F znob){rzM+C8%?LJA>DM^XgV#~blPY-E!lM1XgV#~blPY-E!lM1XgV#~blPY-E!lM1 zXgV#qs(T&sui7Ml#S0xO&n@G{3mtm@{{9HtO1#iPywJ9n%D?aZ5%Kya@%kq5`X=%E zCh__v@%kq5`X=%ECh__v@%kq5`X=%ECh__v@%kq5`X=%ECh__v@%kq5`X=!e7{M2ze#+*NqoOae7{M2 zze#+*NqoOae7{M2ze#+*NqoOae7{M2ze#+*NqoOae7{M2zZe7V`^DIB-!JBZ`+hM; z-1nQr_nXA`o5c5<#P^%T_nXA`o5c5<#P^%T_nXA`o5c5<#P^%T_nXA`o5c5<#P^%T z_nXA`i*theesQjF-!IOM?)$|#(|x~5e7{M2ze#+*NqoOae7{M2ze#+*NqoOae7{M2 zze#+*NqoOae7{M2ze#+*NqoOae7{M2zqm%Y?-$n&_x<8p>AqiFL*4hA#P^%T_nXA` zo5c5<#P^%T_nXA`o5c5<#P^%T_nXA`o5c5<#P^%T_nXA`o5c5<#P^%T_lq@y`+l*O zaNjT1PVW1~n#z5@NqoPyUTyOICh`3y@%<+8{U-7KCh`3y@%<+8{U-7KCh`3y@%<+8 z{U-7KCh`3y@%<+8{U-7KCh`4ZZRx&Wtfk%ei#4|Uev|lqllXp<_C9>H;L~ziSIXw z?>C9>H;L~ziSIXw?>C9>H;L~ziSIXw?>C9>H;L~ziSIXw?>C9>H;L~ziSIXw?-%dm zyYDxN?>C9>H;L~ziSIXw?>C9>H;L~ziSIXw?>C9>H;L~ziSIXw?>C9>H;L~ziSIXw z?>C9>H;L~ziSIXw?>C9>*BLr$65nqU-)|D%ZxY{c65nqU-)|D%ZxY{c65nqU-)|D% zZxY|H-BUODev|lqllXp<_y6+d7t^0nV*}Cr+nyveOq1n3c7n-g6 zexcdA?-!b_`+lL>y6+d7t^0nV*}Cr+nyveO{oIIWPkzoMi|^O39ZVPBFLYY>{X(a8 z-!F7p_x(brb>A;^TKD}zr*+>ibXxcQLZ@}#FLYY>{X(a8-!F7p_x(brb>A;^TKD}z zr*+>ibXxcQLZ@}#FLYY>{ra_%b*!$TWbys_T7v1~`-M*HzF+9H?)!yK>%L#;wC?+b zPV2s3=(O(pg-+|fU+A>%`-M*HzF+9H?)!yK>%L#;wC?+bPV2s3=(O(pg-+|fU+A>% z`-M*HzF%KEv5w;V^))2Z#rF%H)_uRwY2Eh=oz{K7&}rTG3!T<|ztCyj_Y0lYeZSCY z-S-Qf)_uRwY2Eh=oz{K7&}rTG3!T<|ztCyj_Y0lYeZSCY-S-Qf)_uRwY2EkhYiZV3 ze7}BA!F2KcLZ@}#FLYY>{X(a8-!F7p_x(brb>A;^TKD}zr*+>ibXxcQLZ@}#FLYY> z{X(a8-!F7p_x(brb>A;^TKD}zr*+>ibXxcQLZ@}#FLYY>{rbHX>npxrzsF>{_+*9Oc&oTbXxcQLZ@}#FLYY> z{X(a8-!F7p_x(brb>A;^TKD}zr*+>ibXxcQLZ@}#FLYY>{X(a8-!F7p_x(brb>A;^ zTKD}zr*+>ibXxcQLZ@}#uWK)?ulRmlgJQb)excL4?-x3)`+lL*y6+b{t^0nV)4J~$ zI<5PDq0_qW7dox`excL4?-x3)`+lL*y6+b{t^0nV)4J~$I<5PDq0_qW7dox`excL4 z?-x3)`+i-EV|~T<>zX9f#rF%H)_uRwY2Eh=oz{K7&}rTG3!T<|ztCyj_Y0lYeZSCY z-S-Qf)_uRwY2Eh=oz{K7&}rTG3!T<|ztCyj_Y0lYeZSCY-S-Qf)_uRwY2Ekh+AQl^ zX|`T>e4Bz?Y1d@&{X(a8-!F7p_x(brb>A;^TKD}zr*+>ibXxcQLZ@}#FLYY>{X(a8 z-!F7p_x(brb>A;^TKD}zr*+>ibXxcQLZ@}#FLYY>{X(a8->+-+tfTmT{h0;R#rF%H z)_uRwY2Eh=oz{K7&}rTG3!T<|ztCyj_Y0lYeZSCY-S-Qf)_uRwY2Eh=oz{K7&}rTG z3!T<|ztCyj_Y0lYeZSCY-S-Qf)_uRwY2Ekh&u&;>@%{QUET)U^7dox`excL4?-x3) z`+lL*y6+b{t^0nV)4J~$I<5PDq0_qW7dox`excL4?-x3)`+lL*y6+b{t^0nV)4J~$ zI<5PDq0_qW7dox`excL4@7JH@vA*K_^=Fz)7vC>*TKD}zr*+>ibXxcQLZ@}#FLYY> z{X(a8-!F7p_x(brb>A;^TKD}zr*+>ibXxcQLZ@}#FLYY>{X(a8-!F7p_x(brb>A;^ zTKD}zr*+@2Kig$}#rNyaxS1}#U+A>%`-M*HzF+9H?)!yK>%L#;wC?+bPV2s3=(O(p zg-+|fU+A>%`-M*HzF+9H?)!yK>%L#;wC?+bPV2s3=(O(pg-+|fU+A>%`-M*HzF+9H z_{JCOE52X%JTP5+ztCyj_Y0lYeZSCY-S-Qf)_uRwY2Eh=oz{K7&}rTG3!T<|ztCyj z_Y0lYeZSCY-S-Qf)_uRwY2Eh=oz{K7&}rTG3!T<|ztCyj_Y0lYeZTJgV132+>mC@U zi|-dYt^0nV)4J~$I<5PDq0_qW7dox`excL4?-x3)`+lL*y6+b{t^0nV)4J~$I<5PD zq0_qW7dox`excL4?-x3)`+lL*y6+b{t^0nV)4K21y+Ew5_ z{X(a8-!F7p_x(brb>A;^TKD}zr*+>ibXxcQLZ@}#FLYY>{X(a8-!F7p_x(brb>A;^ zTKD}zr*+>ibXxcQLZ@}#FLYY>{kk`d^%dVQbXt5Hlj-97g-+|fU+A>%`-M*HzF+9H z?)!yK>%L#;wC?+bPV2s3=(O(pg-+|fU+A>%`-M*HzF+9H?)!yK>%L#;wC?+bPV2s3 z=(O(pg-+|fU+A>%`-M*HzF%ll_;#pkarka3S$x0HY2Eh=oz{K7&}rTG3!T<|ztCyj z_Y0lYeZSCY-S-Qf)_uRwY2Eh=oz{K7&}rTG3!T<|ztCyj_Y0lYeZSCY-S-Qf)_uRw zY2Eh=oz{K7&}rTG3$4<9ztCpg_v;K#EOc7;{X(a8-!F7p_x(brb>A;^TKD}zr*+>i zbXxcQLZ@}#FLYY>{X(a8-!F7p_x(brb>A;^TKD}zr*+>ibXxcQLZ@}#FLYY>{X(a8 z->=u5brjz(bXxz$tbS8BnNI89)P+v#-_(Up>)+IcPV3*)g-+|=)P+v#-_(Up>)+Ic zPV3*)g-+|=)P+v#-_(Up>)+IcPV3*)g-#o*Z|Xv)^>6Azr}b~@LZ|g_>O!aWZ|Xv) z^>6C>TnOmvYL1Y_|NQ&6plv?@w9kL?x1g){7f{Yno!`jPr$PL~LE>jR1|;6E7ZLf3 z_c)06IEeQ+s2^M6{d$CaX6986;^__I=?&uP4eD){c)#v5e~I_?56drJ*&troAYR#^ zo?(gi^%e7%cwc8SfAOFO@t_9rpa%8gO1!UQnZLyQdY<`dBONzyD?a67M$J>YJX9DmFD4WaTszysjNO5iF_a`jupc%J0yScsXKX8_lC zd|!_FRCOm;Z9=a6C(K9U-LJxQiO2OFeV0+rs!z#P-;w2+wf8mBy-&#!?_-AP)mUOa z)tDs9vtS>SOqX~clgvlreax41`DRo#r*&k+5b%zWfo zo1c@JF7bX&WP5ObbaGF)m*CfnGo@Mx&gy|CRYZB%o z@xJC^x;*>vH5K!bX9T{cV!Fipnu_^Iysz1qF3%KvO~`yid-pXV(5gv>|cXQtKr znwI&9rj6@6_G@6eYWp_kv9AI1mv~<@Grd|%^S3q!T`R_1j{oQz5fblfa^@rPzUF6o zbuYmD?Hq!AH^|k!1G&1VAWOX8Qy?AJckJImmUx`&qJ2}hlzoX#jbG$(YSCehR(y^N<6N`9`8CBugleM z>rk&MhFtwNAic`-m+Z$yyqAY8zttE&E@Ng@{Z0D9>sv$nNPUCojY0IrAbMjEy)lU1 z7({Qx_h4Ob45BywTfZ})<4rissyegIO<}EX5M4cpt{y~J52C9F(ba?K>Opk%Ai8=G zT|J1d9z<6UqN@kd)r08jL3H&Xx_S^@{b%Q^N;ku~CCsYNQ}o;}to04@{0QIo_UA`I zo*xByeiY>SQIO|HL7pE4d43e+`B9MPM?sz+1$llHe@h9>l@@bX^`inL7tNac}^PSIcbpRq(PpO26;{zS1o6ED@x27`y#(>S1o6ED@x27`y#(>S1o6ED@x27`y#(>S1o6ED@x27` zz4)^g)>rP`!mR3dl6zsj&(-<{@plFBcLnix1@U(U@plFBcLnix1@U(U@plFBcLnix z1@U(U@plFBcLnix1@U(U@pnP{!hVJ9U*RyT`ua?N!=8++udvoPh>tOdk1>dkF^G>b zh>tOdk1>dkF^G>bh>tOdk1>dkF^G>bh>tOdk1>dkF^G>bh>sE4BlclreTBoU>R&be zGunP?tgo=vH;7+1h+j8|UpI(fH;7+1h+j8|UpI(fH;7+1h+j8|UpI(fH;7+1h+j8| zUpI(fH;7*s+AsE(WPOFhtm@M?{TX{`vcAGv-ypv9Aine&6+WKfwfJRygS=-HPo&nU=yMnT>)3i6&&koSy& zyk`{TJ)odLg<19eGP?%B-@^I|Ykh;f zPZ#8Ux*+e<1$mz?$oq6b-lq%lK3$Oa>4LmZ7vz1qAn(%!d7m!G`*cCxrwj5vU6A+b zg1k@X-X7Lhp1p=y^*u^kL&9Ig`U-1(gSoe0hgtP~;mY5|`U-1(gS;Od z zgS;Q@-Zs`(ydPm!eJ@_TH0qPl`Ud$9K#=bM1o;j?knaEl`3^vk?*Ih(4nUCa00j9C zK#=bM1o;j?knaEl`3^vk?*Ih(4nUCa00j9CfO`wszv3MVv+DOB)LSL2^$qg9iy+^- z2=cv)Am6(P^1X{7-@6F%y^A2k{Ok{OFADPgq9ETd3iAD;Am1+v^8KP9-!BUC{h}b>FADPgq9ETd3iAD;Am1+v^8KP9 z-!BR+fBJsW&-||Tyt~OOJF9-TO1;6tv+Vx7>X#M{v+DQR%!7oz$mxF**7^qd9$k>{ z(FOS)U6Ak51^FIbknhn2`5s-6@6iSM9$k>{(FOS)U6Ak51^FIbknhn2`5s-6@6iSM z9v%F3x!TtTelus?e|(nu4q;VCcnH0|?kAij_gk;VuzN2tw!!e5W!t}r>9f-JHmh?K z>m{u9g}*M_epPG-`MxOpb$Q10ZJ93L7lpqr+kRC{m+y}bopL1{B_y(A7r|GFB<;3Z2J!~UA`9$e_giy2bnJ4i-x~0+x~-0 zukHcC{@xbTXW8$B|MV^={B=$5bxM8VugkX2Cfh;2iw=KXwtY64F5g9mzb@N8n@pGQ zqQhU8ZJ$l1%XiV?ugkX2Ce!7+=#M@?CWJ>$2^$$#nTHI{bCn_Ss~*d>0-5 zx@`MwGQHApz(0G}byoczex=c|zQXX=W!q1dZ6e?Qhrce{ezHuL@BhPJmu){;rpx#L z;jhcKpDfem`~UFQW!q1d>GJ)5`0KLmC(CsC{y+S6+4hrVx_tj1{<>`Y$ueEO{||p% zw*6$8ZvMJ#`^l0kJr?YGEYoMzeIF`~o%I!lzb@Op$*jBVa{+%{wtbVCF8f@-Uzcs) zWTwkL7x33*+c%l%vd;zlb=me!X1eTi0e@Y#eUq6k`&__Zm+b?rOgDdBwtbVyvd;zl zb=me!X1eTi0e@Y#eUq79JwpNed!tOBRrfcko{_P>!tmE++aH{Dm;GGeugkVSIMZc6 z7x?S4?GMg$+0O<3x@`M{GhOy`fxj->{@_fP{aoO$%eFr_(`7#w`0KLm56*Pi&jtRv zZ2N;VUG{TRZ$r2BijjG0yU@u{A1v%bRc*X8Hy9%0>O-y-qC9W#1zB>+&LNlyup*2>!af`RpYh*|!M(y1aDT2bhoSTLgbyUVQ#> zOqYF&;IGTiE--=VvTqUmb@}@%r!ZaiE%JA(k?!wJGiFxZud4E>u)f0Z*QHn5JjuGt z{#@|arT1^1#B|x83;w#)-QJtEc7wkzUGl@jWZ9n!{<^f?6D3{t=Yqd3ow-gKOR_%~ z{B`N2j^$XgKNtLUY5&tp-^u=5@Ykhr?Wgg$vOgF6b!prj&oRC7BZ2+Bb*9g%`?6K< z*R#ID@Ykj8hyRUrmwo8quS>gZ{V3CAA3FH!QhseJ(`6qz`0G-?w@Y8hK6LQc)!tdI z#LGT(@YmHo99+_6A3FH!YR@b`o%zc?bnw^J+RyPA(`6qz`0HvP-8h5kvJahqTL9_) z-2leSs{0RC9#Pg;7=FUK9Y&WiFZ(URUspGD%hH~*-y-~Vbr+2&b4T`Dgukxtq)w&3 zWWPoD>%!tQO25l~i}2TlALc9Zvfm>7bz#ERC4bp(5&pW+d!91hWWPoD>%xeR&#>=g zzeWGH1M6G)ff+Na?z35Wyjfpi`0K(IE0^&v`-;L}7xuoUw7={t3V&VL?X_|)m3>9w zuL~QUTF$-ZuL}?SSkB?HuPFR=q4U^s-j;nu;jas0*Ddj~uPFR=VTHjZPuW)#{*A|-ly#Tvp9_CoT)%Zmm;H0$ zuZv4QU(#j&T=?ta8Jm^-W&d3G>*8}`9%6Z9|6KpJ3F}+EkHZ-A*Tn_zV)9qU+&RlpJ@2&;+AKZdoI~08veTYU}!a zR~UY?`1uaZbC%j4yn08H^%d6o!e1AE_+&8qMfO97zb?MqzUU0HA3FSXvCq=|7%%&w z!(SIC9&jtuWj}QI>td&|H!)rILx;aEuCq%?m;KP;uZyETDCx2vI{bC^BKx7k zUl(^AGl2P5@4$lnyFE-de_j0IS?t-Lnj7|4it8roe%N0retG|;j4{7i9Ng)m^4kx3#eQe^Ae-MTu0C5~^P9y_ z#$U*E^P9!lCKWcnSzK|U5@UX|IO^!a<~NHIUnp#Tvv^&naxC+k#hd3TWvkwCW}d?E z*Li*6uk-rCU+49Ozs~Cmf1TGC{yMKO{B>Sm`0KpB@Yi{L;ji=h!e8h0g}=`03xA#0 z7ydf0FZ^|0U-;|1zVO$1ec`Y3`odoq=Uwz-)>jyQv$(<1=QG{>X7REKoyq1mi?2L; z2HE^(vBUbOkQF`M)`lY<{!2?xH7<&2JXx`Me|9{AO{TD~}+X-z+Y< z$6;jio5fw0K9p>Jv$*1)4k4T0EMC4)Ve^~CleQ~tezW-8=)&eVi(L*Wzcs&E{OZXL z{H^)T;zgSsORm0G@JrVE!e8h0g}=`03xA#07ydf0FZ^|0U-;|1zVO$1ec`Y3`odr5 z^@YFA>kEIK*BAaeuP^*{USIg@yuR?)d41up^ZLSH=k@*B_kOGIQK0Vdo5hYpc4j-6 z-z?VWt;yy$i!1iuoNRuxc;Jrh$mTbTS8ZNTHosZyw|yX+-z;`Jq%GO}W^v+*n~=?K z7T;fN9kTh&V*fsCkSm`0KpB@Yi{L;ji=h!e8h0g}=`03xA#07ydf0FZ^|0U-;|1zVO$1ec`Xex58Lo zVffAB)m;~6y6p=YS8YE(+4hBu-?f^DZ2LmSgO{I+Z2LmS4(;b4+rE%--Q${(ZC}Xv z;Dvu6+rE&o%PHUC88`NYj87f%9@+MVjO#D{CfW9djME-_m2CS$#^bl+Gk5F@8HaUw zk?FQCWZd~GK6A&ukg@eqg>7HRxbF3ZZC}Xv(e(0L+ZQsGHL>KmlKLFyZ%zCr36q`pDw8>GHL>KmlKLFyZ%zCZikxcOD^oj24SezRHf zyZY5PzSzIQT3`6;Y$>wF&p`0IQh0r=~D9|8F5d>;Y$>wF&p`0IQh0r=~D9|8F5 zd>;Y$>wF&p`0IQh0r=~D9|8F5d>;Y$>wF&p`0IQh0r=~D9|8F5d>?_}`vqLrFx~eH zr~?mrah}*}t8D|g_qN|z+!f@WtGyKLd-`Pj7ypkK{5#^n_#J)^Zn@8-x>rwXN&bWV z!SSl}nx|Vlk5}cxo{DS%06BnNSHj5`$@nq@uQ00$yW4~4H$^NYRo&8+3 zKl{JxcaDpy-$Pa3hOR-`O6Xf7LIjBg*6bj&gdxqx|0QmQPc^ zdpg?9<573dhg{`PmVWp0Fuf`#`q9fzmVWp8GQDaCvh=&Rn;+Nv-P@Vz((m3cEWh+! zkUkAE27-(Yr2BYqX8w|oj~}K>o=I5q_xONzm{~qj1|6#&kKg_>A1^1;owY8%%m*@@5Ii)VYtk*xx=c*;IzVDTn&u@3exqCE%C*5~Jy))7m?QsFqx9Hrp-2!_Q z{`-O#w7Y3USEhHk@q%{!hMrH}ciC?3mfY?<@&`S-wVQBd7xJU8c5C-to3qI~uiU-e zA(Q?>K6c0M?VelqH1hj@>fUbpb|*Hak2~Yoruc?OjwBS zkx`z#>-Hg|oQJQy7a8S0|AU|E==C~coxjw3`mUXhtoQg=-rb|#^BL59t9s9W(fu~A z_u~$$Z(Z-@dA-F-^5rKZ#Nv*+Y{ySc1Ah9 z{ZW4J7xY)(VWnTtkIoOB+_l|%olE-GKXh%k_Zy|ZmOSr*cBg+-`m6ry3)+pn8HL!`mGO^zC-*S z2X$Z!@>ycD!b-2s|7DGOFY{l~j$8 za}exv5bSdhjK0Gh1p6EW`y2%O90dCu1p6EW`y2%O90dCu1p6HHbj(4I#~cLv90dCu z1p6EW`y2%O90cneM7{j{3HIv+>aOF~+0*@c>hV5*k?!*s?DH4w^B3&%7wq#F?DH4w z^B3&%*VFyFgLuCl`TRwU&tI_5U$D<#u+Lwx&tI_4U#~CP&FcvEI)c59V6P+C>j?Hb zg1wGluOry&=;{BCbClK>j4|NnC~XH%*BG#$$H0Cb1OH!KSNQlx`+I%CUPrLk5$tsY z|6e&*|FVuc_ra`}tgkQz{=4*9@tn^wY<2f_m)8;Leq96mbq(y-HLzdTzY6l+79Gv+{M&=Y`i1b@yvM*st|qzt)5O zS`YSXJ=m}HV87Ob{aWwo|El#iw3>rD%)p)wY0AQNHE{P`Z%7aRFpB)_AFoNDcbq#R z{m>gONy|OH4*9u{yQIgq-;@0DxzkZ8!z^dKJV;5L99e4Yc&ZV%+Ly;eo;bdw*GYVxRV^^B3pg=POsG0(`yo6lYG#gj6r+Kanb%vNBc`T z(O+JE^rP1+9k)^|#-p7N&&!a%9roOqudiQ}e9gZ5)`tFl9`bQ3-BjDK{ipoxSvyXy z*u4*90QDa90QDea11c=$6qkg@NZzm z;x}OAfn$J?H;w_W>gDNeCB9DbsgwNcT4g7^GQw0^$*i-++;a^h;ZBLp*ai-tfyuYF9r#f&6H{?Q8undO~ArIBpd~u42fmZg3CFfMY({ zp>NpktqHaL*6dOD!QZY53tsg^t>qFg*U5MeReYVq*GYVx#9JAb4VS)hV(4-9V|Cpc zcMT(-+%3GnZe!i)N1kW-u4+;%gFLlX%3WNt5?yId{A8)O6izr?H%0EYv

-SXkd(GOD z^AYV+#e2Ua9{uj|=y#8|axR;!A5+!u$@)E2{r*%^oYs$ZT3>CeDjxmr@#uG-Bh0h9 z7SzeLqfV|JY{TlBf^@%jARcWP?0kZJ{Mu0`*N!?|qpNF2om@NWa80kS9d)?YSJ#d@ ztO4YFg7g~lm$d=ot7|UvsjkJ$zq&^AxYf0r<*C}7<*cstEPu5IV7)MQaV#8P(tT~f z_K|#iZGilJZGhwY+5qM8wE@cMYXg)YYXGm8pXaS?eUM&P)z{YsjIXY_%tzYO*9JUp zb?s((s_QT7Ql01PaBZp1|8=m7duTj-?gx9X>`oe2kb=|==#IL`&hBWn; zTz{F4W1udGuda8@r@9U@|LXe4<5t&AmIuGVZ;?lJ{bl*9>#x^~F}OBLJdc6jqU@5t zUw?URl=ArXm)FMX`pavhk3+fsGF{riufI5^Uw@guv?u?~%VXu_d_f-4FKy?1X0~wo z)SGKK<`VhGI`EnY-!tZeIX)u~yk))G(AQoj&-u)`wG}^jh`i-{{cHA@Y-u(7H?qan z>^Ee~19`PYo|ZR{0k&f%9K+Lb3^3wx3^4M+F~GZF`?Qhtt!Ql8m@)EDt}NVj7mAF>@2`IGIKI4&7!__vbJ zxpnvr7!+rX{+b+Uvq7hc)!Q|A6-YP zHOzmtCi$0KUw+McL)LXc*XLUIU$b69KjOTH>#AJuaNXy1LGJN?^>tjz_D`)jtu8zd z|8K5as&)QzNwXdjARQ(&`?NeOKLUP{XY5L8xtt zHdw3fS!%dHtL_1jM%~b^O*Pz~RrfwM+;52{>GyyZ`@05f+fv%!?*Y*- zZMDBD=Jj3f6Mw&dw>1*l^*`Tf611X?BB>1o9s8#^em5Ld66w|KWEn2F_F%DBBbLOxEDY?jsZqKI0hK` z<1ZL#_%|?O@f$GmKwe?vFtlA+6Kn}TiyZx#UJlGFw&(R*mp=rJ~### zZHd2Nq~YJdXiFRej6D1pXiM!ci;Lcmhke_eyy#00S>Me?zWLcLt*ySS#=~XShR;>w zWVE&IXtJeQo0s`(vDOz`GTrjXmRB_noAZ60YFr_mbIp#KaSWs*9&HXrK9)Zj`QtCr zk%oUO`CMjwH&+HD599?#-c~O%>M!X$Mip;u)s&C5VN?FrwoS*iHg77A^+i)Tqm)15 z7^OTdk?!@4(hgDD2l)rY+c9xmGSaL(WW-AQ2k95uV(?#-3%>=UyvP%b zdf-@K)DOo4quw|k80~>FgVC<23mEN(|KbnY6~_Q09mfD89>)M99~=XW{P7ozH2fPF zvG@%bdH6AqH;#dH{E>9_9nw%n$%lQ1bks?X%f3Up#j@|fXd5X%+X?AtOQ|pW&f}$h z*mp=rTjDPm$Hg(gh{Z9$D5sU5jJ&nKz!(FFLkt+@!f(N76XXd-Tj5w>)DOo4qg`=4 zFxmsh1EXDWJg~PP810HZ@i+z;`QR8}qf3>W}Pr1e+-LG+Azy5&H@3;=NA~~7|dZX&OMmJ zU_Wnxt)2f3=f>aHkQmRhMz#KGTDx+7p)dYZ){v&*HZJh#lJ%>;FmEGx^)ai|?=W(H zaD${bX!@iMYk5qg@XumC{$#cKTgI1sW?y?vXU)G+Vj49@@@#ygObDR-+M7{!$x6_H~(#qzDszUG@NtZ;@(yqtKPN} z)2K0$C-bkyMuVi2eavjryH)-3SI))$`eaiE92+*eO9bL^QyvqpIWK@u%`>3eby@V!{#n?YOQvw)xWq(;jde+Q9tjxg&%%- z&8GA-ZdF5214gZB4wqF=oH(q9cTW9i2R>Bk1?#|G)g2IBk1? z#|G)g2IBk1?#|G)g2IBk1?#|G)g2I9T7dZWypMwu^-GG7{H zzBI~wX_WcWDD$OJ=1Zf@mqwW{jWS;vWxh1ZeBt@W&#N+D8fCsT%6w^*`O+x!h3S6Y z_&|8t)kao8B3gBz7CP=_|Mi4Gg%vOedX6{S+{U~<$225hU*`{7GtgA z^Ig_m{H@P-UGK?UZjg0jgRC2Wb}f+c{QLR8T*v>T&i}o3oU?Iyhm+f_Fnn<1Nz;~W zVoyKu<2#zt!Jdxzh4LJY{SPm{{cxQ*8n@i9@X14GZ~SQc!q;y!d*ccl7oL53v&PQL z7M{|%S>uEsPU3MpH#BQ}^M%46E!nK`g<9e5n>TCB*Z!Qf3}7z<*vkO+GJw4dU@rsM z%K-K=fV~W0l;O+Mk7hZ4SstW&49e;3@yO??-O6u~|CF^0B1=g_y-E3UMGzxjQX}1R2Y5n+U-AQEd$ug0QNF~y$oP41K7&|_A-FI3}7z<*vp{o zV+mzLI>wckQ~9fdmTIcYGVd+bRL5Q?EZtQ16W>_6sZHkEahayJs=s-erZ&9v`DL2g zcIjrzHnlnKqrESjwLD-i1K7&|_A-FI3}7z<*vkO+GJw4dU_Gug+6U}o#u@2dTeNJP zbW9mb8}(VBahIbC@3Zy-jekG5@a7M3Li70d1Kop z3-2?qdE==+oXEa->!Rk3-@RJ+`!3BJ2R`&u`ksReBmRY+g^|w^rx!;4Qw}VQn&f9oYL0 z?0pCJz5{#TfxYj*-gjW{JFxd1*!vFbeFyfw1AE_jI{MDz(RX0)JFxd1*!vFbeFyfw z1AE_rwZFif*EpVYgmqu7FxuqyKNdz?^_jI(0$D^%0AGD$8kGA#WqRqWL=sPbb`p(ObzVmt^-Rp~ZZwKV#?SuTi z-EdrQPn5^o8Rhi$=h&J&_Pzsq-+{gFz}|OY?>n&f9oYL0?0x6ysJq9b zO~BrFVDCGy_Z`^#4(xpg_Pzsq-+{gFz}|OY?>n&f9oYL0?0pCJz5{#TfxYiM9ewBV z=sU3Y9oYL0?0pCJz5{#TfxYj*+F#(c-Z`de-i>&(Fxq7AmkOh;c6*{Q+OXNU!f4yK zh80Ge_qnbx`tIqo3#0E2KCCeMZvJh4N*}exPx0**D2#m0{H(0&kpDU_6vlBEd89DP zGk$bolymIR!sxrhZ!e5`y>n|})ZNq3CLWKr@_f*SoKE-VXY?t@t;K-7@4()7VDCGy_Z`^# z4(xpg_Pzsq-+4Of?(t|7u=gF<`wr}V2ll=Ld*6Y*@4()7VDCGy_Z`^#4(xpg_Pzsq z-+{gFz}|OY?>kRN-+4Ux4(xpg_Pzsq-+{gFz}|OY?>n&em##UnUiEt}tYiIN4C`CJ zN5i_;@7=H-_Io<4ll@)~>u0|Q#Jbw=4fVd#+1JLt2KF-eS{h{ldl|r92C$a_>}3FZ z8Ngl!##HyYU@gPH==YK+!@u*s%qAR{&(E(c-{Zi{p({J_40EO*v~~^ zKNo@hTm<%W5!lZ~U_Tdu{agh0bCIX}c^L72e)e+_V*FeL_Hz-~&qZKA7lHj;1om?g z*v~~^KNo@hTm<%W5!lZ~U_Tdu{agh0a}n6jMV|hzzK;C9-Y)(1e`US>yDm}s%XJUT zFV{mbzg#E5{Br#S^XvbGF7f|Tr*+NEuW?v=xb_Hk?GfzSBiOY^uxpQC*B-&HJ%U|( z1p74(?3y0fuW^k37wL+)#vy;d#)1FU>nOk8;aGmX1N-$3?AJT6U+=(vy#xF84(!)E zuwU=Me!cVb-`C#%v$Z#_cW6WO*KDR^fYD#jH^AsG=pJD77xWM?`U^S<82ttP1dRUj zdvo-c-?O8?pu->r>A!0f|1*sO*E_T!`U`q5+uZsKIxrah1$`Kd{(^1{Mt?z12BW{A zGlS7zu3@5IT-!u{L5D{S(tp=-OMiKLVtwoFjCHTKKi0$EFIyclwa)Ho^9>t47+&b` z4*8N+_lNNMSLD^&+!t!?z9BcZ866s4|B$@qW%q;;PyLPD;eva@sppO*Z`JeOFyWvV z+ak}aT0asFK6hcJcYXcgFm#iZcLba zskNBC{rn@t6BjN=KC$avVdFQOk+=S2Soq7-%wv7A`>^owpU)=${l;P8$9ZlhU-y?s z!jn7CRzrC%9(8Xxwa=X7ZN}Ug-WjnHdF>VM2#=q#19_2m?hG5hx*S5@ zA&w2rhVEbZvk75?=jzGlcAgmaUtn?atq)HKZ@o7!x!1d6!^l4`m2ljA){xY<{w1b= z_NTkk!UudxK5XIp(+6{{#F#ZV8lBo)zdE_|2KT0m7A?HmTO-nio2|_Bl^?q!ExP^k zq3*#`K!FXDPk7bby~W&$Mm+~ zxYvaA+RJy4FYP%c?RDD>^12g-r>7QPjC|0J1Jau3-ACT?v_a{Wp7S!#EAH%{8rI*F zeC>cc(~Fa~BsZKeFx|fTUgY(+z9(IH;R@sprjAVA_x&UJ&;^F3=`S6@JP&<*XzDq1 z2lB~FK4RbYTZJ(v?>RB`7`+mC)6QelX`k;yZhOJ~X|rL4&zbTNkA=4NV}WrjJ?<~d z<1r`?80FEj>2Ea#WoEpUS2snzh>NOJjO77 zi!rR@S@Y2tjBUhYY-7xWG3IAB{x#1Ywd2|@_t`Re)y1c!Yp$J0p1#T>Kg$R61$kn= z=-ko#H3stt@t8-LUtr9ynawrLvtf;=ScZmAhNeH9-kto;edV{F59THqb5rN3=C3iB zvxvu>#asqsF3)UUYo4Q5SiOe!x$y1&X}%e|k~evF$j|b@yhEOtn>q(I{|go!R)=%Z zuJcVwFD=}Q{N8($)9#y>^pp1(l=fTm4*@Yt{rF(|D$PxP24zM(%B!`og7}Oo{sJpg<{#Ikq zK8Q#AXj|!TH3n^nc(kFmr~X!B(9VcQJ8PTkZ#4#efq3+V_KW^jW6)oSM}KMG>2Ea# zeTsPWsrIk_R%6ibh)2Kc7|`Ep48|(rF;;cl>Tfkh$C8d2{q1>+Ji)Qotn;w&^=6~V zjh%*vMSC^pcwYU(k>Re^W&AJp!|*WQJKr*<`yYpe#*S~1hg^6^`2Mqx$eVBeP&oIp zX8diZN5_S^SDlZ%=MQ7UrhQtFJ1m{T+4J7Z_{Xo96z=(~2l?x(Zx5eeJdnKYPPcJQ zh&hNgA=ZjutQD~)1Y=EzwIUd6MXU+ISQBEc2*z3w>q9WshcjC@{xZh%`8Dg$nH^Wl z`D@m<8n5-jZ&4m^2aJJVu9<%sgLuT~+E~}y+MZf>j0fb8@vzXt?~Zx+x*zmx+I8G3caq?TojE+70*7N!F%ogMmu1n#Y`ZCA+4!l2%>OLFO_gZZ{ z#~b1?-hS)Y({kdso)5+(7-Le$r{=FQ7`KSWxYaSNzttFwZNy`2>p0inY7FKh;xQj} zZt8C}M*B|NR)5>}`%zr?9uo(Kwlgjng>iEFN`u1OBTnNOyQ|BXu>Hr!kdJA&JAAa! ze&j7qy)(4hWmEF#)rW-1>ozB!dC$NwXu|2_2X{)}2Q?DuhC z+{exA{towg8sop6*}b9WuVwpZ?mac1UsFeIpPAkN{xSyjLSOtd_t!X<=kr_pRPU*^ z3}EDme%HRhILF+< zZ!s7CnR%ge4f%MUm@i<=7o9tLERC6T_9=|N{+XJ+93JL9{4R3rGbBvu^C5ZtqXtqtLLH$UeKMvQ^I2osaB59Rht>og2@D+x z`VtuW5;P?+G$rUrVCYEDmzZw)5_BXmbR_6YVCYM~MtAzJe(T5jHM-W!%BJO?nO648 z7#tVv@M|=;nY9~!i+s@Lzedy3_?h*Q>UEkY7{@|CYI|bLV;*75fBE(xa<_&Fq37cF zlbcyT?)P=G8e-~JnHpaIur>LQ1Ez%|`t3sAX18e}OzKGPzu43;vP*aJiIXOVH_z@# z{`lDkIggMJ=Fz`%PU*bHalH(fYhcVZop)L`jk#~9Zj4{KY;Z@&la3}| ze8`|M?Z~akm&5^_zsMi+_n(=|S~le4d46@oyX>Qnd)T_`Uv(?#^=IA})?I4`(>Lv%!#xYVN?w2A`@>T6 zy+XeKt`TAId?n_9{-eWr1OCALFW&psu-hx&FlNctH-;b9xQ6`961Rt$wH4Y8ZH{(B z3>fXHjP^u2+Ed$B^Zc#ttodmEM_6CrSPj+}w^$#6AGAI~-+_;`zI(v>6r8P3e`|kf zIW?bF^OicEu>AP2ll3+7U)B1$qm2PD#=z{ee@#Bs#)fjQo##p{+sEU=6^pbWpJsZ( z1248D?^>5QP7s4}@>|D@))Bw;d@z>47)v^?G=Gi37(+b97{(qLV{c~TQ1hJGnAG2D zo_E@~MgHsAxNU9Y8N88=XXU@oThdn>Fq&f-lp! z``!}Md!Nzigf+|D|8a?j(|J1$=DdFQ##__4z7LY`-Lr2x=9_28pY#}(mhHbZ^ZDb$ zx2FYnUXA?4nz!>=8_rjF)`n+rU_67vb2qR*cLU?O8=kd+@vIHc;J|nWhv#l!f9?jx zbGMm2o6~sB^VdA%(|9cdev9LxoHKiF_{$i?qmDCs=BVv}7{q&9VGR88dF3x-5RaId zJ(twyp4$F+c8TAj4YjQ>PHo;Yu({$ahVHYPv#_26*iYMYS1p6AYR?-wQJoG(X&+3s75>4V0P45N-%k396+ zeqqYii;)li?#A%{(e{_GkIeXRNWhn4FQv8S~lgZR~wzZ^Pqk&px!bvG=FF4Ue-u z``O;cesA_RJZ|l+WUUx4#^Xlr!A8f<3SKaA5B3W>CpiCrZP?(Z&E`|jZMgYPtc<4~ zU5Dk5U6y?s$?Gs|#$mx{J8Z+!sqd0`%|Y5WT=V6N;LtC-uzl6xViTNl9$jZlmUZTw zJTLKJ?I%4y*zcd$;d`;xVa)5Kw?6NIZLB?5bJN=!@1Jd~{abU>I~SjwZLG6fbJOz) z`;BcZzgctB^C$b9Z7iQ#bJM#EzAv`1?#r5+-aYbNvyFAv*4*@Bfa8R1tT?gerWZdP zV{Bu^m^C-O*yGq>8@^Nfx%M$*KX>)D_6En#o*iqjgcfJRwGy#Xp5=nm+8x5ezaJ93 z>SPL*ym?G;*}I3)=lxW{L#Cd=etTmDf7@|J#(59cIAd#^pJk0R=5bz=ZLBq|x#>NN z_ro^Ueyq9a?UT>KHr83Jx#^ve{lGSRlpn0Q>G_9!DE7*S*4*@b%f4b8KD+%~dmq}* z9scO0_;yZ>O>lRAs^B#%*Fug~w*fk9U-`U$AfV4mMtE-oj(GnS1pn8qKi+!n3p>Q@9T03qUxU(yyKsf5IXj*;FXRi zz<H6dihSHU;Tz2F*V^FyD_2DB-2 zL&hg9IRL-@I4Zc(nZpn^Z>QjO#|}f)$hCrh4m${wv)JPNOpASRy}}|H|M4jq9(&Cf zoGa@dn3y_8a1Q_N@V)9>!7n#$fs!7J1uy@!0a|3-Ab9ELbx^haLBVG`t%s)c@5pkT zm-5&mHhk}v4P(oOv1P;dmJMUe##)E>#`f0U7+ZT|Z0(J)wKvAR=Kthe>>pmo@(*L) zLwbH=|Fezdf5w*o8C(8mZ26xtum3-}JB|ll$BGBWRy;7~{rp#AhGUHFtr)Y`OfU90 zw%NvtZN^q?Gqz%zu@&2lt=ML4#WrJp?*ET`;r!+Gt^8$dvKkI+19&&x=HLd#0*s9Nr zt@_N^s?UtA`pnp>&y4w8|37Lz*CJk@>x})L?Q4|%bM1Tk|J?I)E#jV^#~Cvhu(z@2 z6!tbe&i2eT>}~!lyyHJ}7Hb`z%h=*9j4jT>m^lm2Wz2lXejR%bWpBgdY|q@v-sZo{ zv+UR5xxA*u(HL7Cjj_ei7&Aw+=WF(N!Q++vqp{$p^S8jrl{Q>+#yZG;!e+DY%1YQ;wVv3t z_F4f@z)SGS*Nb7ma@+b3%Pxcri#%j}=GOw6m*Xi@1&2M=Hcj&l4&h`J=e|mB9 z-@V`euFv^goEO%)7+dFJY@Lg-buPx%xft`g{%*3CA91(~D=0CAMLo+t0O+G5fh4 z-OEZ|I3L~xYwOh&PW>)*H`IIQEqGL#2`QH!{apJ!+s_SLKD-w1?Yw>pCU?9e?+Th#ISCISNpQ&q z>tNEcA{yHqnXwl9u2d5IYQhP45Ed7-VfVY`?2Pxw@*F`+gN9@=B9f_@&nsgez4}I=O6YV+gLud z=BDRc_CMQL{|Qo-^H;# zzl%%ny`25H{X0GTxjfG6@Vh>H8~f+l+t}~s!|*~U7%H8(w<9m zY-2sknw#Dpc%N)z?bDi@-u~^+h;&}IzxG_9! z$TpS_t-0y>wp7yJlJ61cPoPoCR`_Bn6V+gN9}=BDQp_8Z$+ezWGL=TG)I+gLug=B9TS_P(;Wv0umD z&vP4A<#;gj)+hp9Z`Bf9^|x}+dcQ9C@IipD>umUuPct|?s=AEVzu*fcuKyu;!U;ck zmsmvbjD;;AX0%P8KiaPeoZ6pR#{Vr+AJnsSewG^7d3?b2f^4IIn%o?A{c;z4yMr&x z9bZjw#7sXpyb}ahuhs%0X3O`0^n|_jA#9bGjPLka0TzVW^6Q_F((uBW?Gs>4x2hIK z#ziid;BjofzmFBVYo549<E{8mhvn(-=-n#y(+$ivBjFetGBXe z&GBOZ!!Y(zbJ9 zT5LTSb3)E*_Q6)*Gf&Qljbr`5n`}PK{{i_2)`NmODhMt*)ep`M)S=1TzoGi_rjXXk z<{xO<5E@?B#XoKGHi1%KKy2`FGgy?_3rZG#2FJU4L#fYIWqcXp1W@7Vg#@Hk>ZU_PC~%9|XA6;C1kAEnisDQ}&NO2b#j!Z?b1R+^;cYtmwsiz%);9 z$Wzvn_lXPM_(JvCRb+g0q#wLVt;J`-UL(E12KWyw@vm1Kbq?wl1s1DzaFd%)+G)f zCe?(T87wQ%OpxdP!4=xuMJbrsQk_?r9+76(2SueOfIUudvV??xay3<_g%g!7ZM~FcC7P+$kxfQ?4&RJHmo{5cRZX9_l1DrH3fS` z`#@yps&w91xYOAWCUmPsch>=qJobiTduwn!K!-Ozkmo7yp)zcAY7RYoJQ?GdhrX~P z+>7n;%Dq;wY^TQdn72zy@ahM=KKi@2fbz5WE@E-7ds7IksmXX;&Q=glu}5b|*B%Yv znzNi8-zI^|*#ybiYbVNyO*M+c*4@hT8S%HAe&FU%MsVGQJ}|jN4fYR~249#w_Ybk} zyTlKk9|k@<&hOP64hG77VcMalu>Gst7Y2tkhW>7zd@tDLE&1)T+!21Hn9R_(67BN` za!f|mtRmQLvL7@l=OuVbEpMn*xCY0D*|&}_9=!Fu9HAI9IY(US zxfGvf?XbqMC0^pt>_@R(v2|IFH}i^vAN2k1BG~-P2a;(Wih1*E3P3%|HOBLT8$)lO zvVt3seV6QBFnMWFeLzQV7=2TR-1`dZ)3P;ziJI8!<7zg88qaDpJ>D zz9%*Lyn1Hc2mB7#knwxZe4uKQC)Ch0>M_TCVeL`sjR~)P>I23LfV3+6;8^D7@X_Cf zTi0p<=l0i-IN$NY2lDOK#O7AVmasIi7UUYd6Rtd<92{94=r>59!z5oQg*7C1oL~FE z?ol;myy9dZXholkoR0yN3mzs2&ON+2TrQ|V_1DW`U5!>S_FhfNwOjRl;AVAOo-S_G z4AKJlzUD*eehr{xRvUg*qcLQnxtG0X!={?8VE60lV$;&s7s?H)A~ZVP7cF(o^uz zN50VG8T-KvC*)`j9uG9Z8S=G+Ei=f8x=8K5)EP6&deLdE|1IV}3pc)N29-%YtBsgci`^34e|!;PZj4NK0H%#z#@j zY!kqrBlEG_Li&uG$o*9UzA5epcUITryT(yLKJdp5K5rs6>edo^&C~^lm1_$34fanW z8i%Qt_5qF`{8X+5{PffWug=v9DvtN!*u%)wR?wJy&b4S$KudTYU7h0-hmY~4bJY+$ zmG0EFv8UiFPkh0HdQFOX^Y8x6VZ|m*aD~1tVST*LIby!6+7#y9_aa|qH?I$C1%E*yQB5mUgLBh-OZBQquS(>%Tqf7I&7SPTT;^D+Z~Z;I z1h>(=VMKt`2lMN(rVv`%lk?pi^NwQUel4yQ=GigcQ1`sl0rONt@>`nJA9Ky%#_;%_ z7x}h`d1*u|s9&uL*Bo;Vt$%HBH5sq$><7jEsl~O+Tszhq460Wv{{CIRQll9>D+o~G zQz3n0N(*>$pqA9D4fDLA-|-qyx4M&_^27%oQLV^&G>1NmYK7wgkh;-sU~_mmu_nw& z&7vCysE3Dt(x0MC^NU`>8ss7JZ^b;45cqTFozrn=zll#kucaV=d4 z`qWm?yG;#x?p!$U;tON_y~zLJP$jE3d|$wIz!~~SwuDouH5lU`H+sutT|@^Np7 zdaLnVj7)0*oigwl7ouLl2M%};f0(co6DTGZ_4rfp0E)e5cQoD`4lUXe+_%->J(~?a z_`rqA8lT1NQm_@A-sUNHnsm$;k~eF7b~CDXONiU3u}{p4{aV6kcQ5gC4e*9P3e;d9 zng{FpLV5Bz`PS@2KHtCn6muvuZ( zZ@X$3WE&nUxb?+qBMfI_;`R)upBkpjEfZa<|H0C(vuaARw zd1nf~_D2Miy1z?fj&prdIONZQ;*%1+C&IyJdjvcFGYKYT+$lDDe}==oZyPk`I0+$< zkZ-{f8NUz_2|Hgc5c^D(BjI?x4T5Woi-Zn8_L2W%A*AY9D134&%?$>pO%X7w!5kTH zx*!6!eqT=Z4Pn%pNT~4?c^p&!ngA1<@8EHKQ7(eMD>O~Ut85Mj^jyvB;Hqtr&}*mc zA4B8A;oQ!>{9J6hXc83cw^6W9??|YdX*ur`XDlWA&9Z;|J~R@l)mS7phnq)2lMZqg ztTr(cdcK+~p5#mF(VIMmES|H>7 z|BQq=*miSes`6Xgm_0QT=0zmZy)=Y8WdG{; z4%$Oyh;@p97Oj^v#>Oim;Zu`MY>&%)$Yy5}+hf*S5fJ}z8?TRNhC~qO+Rf|Z0l#pV zT5pStm&+dsqaGpeABQiP0QLXj8k>OkdyY~$n;bIV@Z!w+1UFbPh7 zU&i->{uHaH{p61D;e<%o_h7ErTssi~4J#}X{IpplbobvVxMH73DERwojtz4i?Pu#m zi9NH=*Ku&~hQynBFl3bE2=^hJBmZpJ%Q0qNSTYHgpPwOkTA2t~<2{Ar%{);r99&bv z1^Z{22u-d_%$uXaM#02wdpXX{;fp6hw&qg=f2b?;B@$--zCvSO(`+r}&NBKN7UAVIe&^~A zjX6$@91)Q1?`?uhjE;a_vlAuGuaHgmC8`Soe1 z;KK(f_UfCc%^9JIE)o@PnRvBE=MZ=-7D3FfLJSJZS%%n{30m`S9a%8E-~8-g(U~ib?wa ztZ;aLXouk4xhTfmHVOB?ADodW_%8W#QvY@QEbPA^5{h4RIvjpgT_N}d#b^E3 z+cH%dAWF?X=q>!Q-gDMReLIIDzV0_Ki{> zOvjnwknmv{=ewDo>g2Rl8@N``_dO$FRx_ysW+>InTI=_6Z87^UodheIZ6@CqF|X3z z@|Ia7<4tJ&#nYF{xK8^iykY~_F7pGeQ`B*n#vEq^)vF?@TQ%l56{v<3Z?i$_)w?nD zIkhTLV~#VEVrBo4?~uCjZ{-Nc(_*d09LJe*xy#`sjXBPa>+~7)bhXAD z=Oo2y_g8y0<~Xw{H(MWHC3qU;1tv2-;(cP_M~@u)`|$^YTdu~Q_R z4M?Kca3*UXQEKBc$uv+xnc zqN0jD-ssN($~>AR4xIX(YH@!%@)e zdKKAbkEyvacLt%jNjK&jisb{!_f$=9#jn+)S zTrDP87#LUAB6v-_c{WHFy8<6>0bUUdr~LCyx_)ia`C?5gdweuB34LM%*pK8K$L5lJyn_01Z=MTU?+x6(JG$;LB( z95i!%oScFF+b|>!;%+|`8=sIks9x2H_pimd#X{Rz1$b|e6cA&rZ}9s6tXskM=vF@# zw(WFad*ip5SZl7qb31h`D(8w?9SzsK^9e4wG6sVBr^?(>BjTV)cQzKB zmd_FY6xkF5Udz`A_707uyD`P4XP!97H|bF_bDSMRlOb_p27@_H|BP|qRdNUK4NF|1_x_((@N=<5 zqgXhIse*qeU!}Zo;C*6pL@fA)<>P%~m!&b#`NU&B3r-yz2fc!v#3sf$7G{npDmK-Y zM}yPK2=*H;z8DQpHi_Rb!{jK4NZy^y9H-#RSg6{sfWdeH?fGO2PiBr& z>S#1%XOc{TgI}Yv!K9zBQ zx|e_6IT~!=sX{Cq?p{FRVNTx|xPNj`GIN~5Wuu|s$?hEUP;+Gzr1*FUK1+RLNX;|J z%yGKVJ?8!uBleAo#lYV;iy1uEzgaZwJW!rv8$814vtDu`L2}_Q=WGUZoUw_qu(^C@ zdhU2|xDg8_4}GM)ji?X(cu7G2FWH@lM zis0__ZsALiFUP$3s&Eu6b6hF-CarVou?NSzS)j~h*xTw+GIN|v!{Xq?^tX~Do7>01 z&km20nX|m3x>2l60fV`ZV^9q2|F|ugdCm6Iu`s#c9LbmH^)b+__Zq>T6vO{!FvX@S z#c+#okCxiI4BuCNr1GPM?W&i)S{N%eYqQp{gXIUqJY%TkL8-5p?0nWA@WE;-G-OaL5jf#iqD`Vk%@D8d=knIglUR zpaVVQW0Mpf$JvGAAo}__!E*xR;NXEwlJ6Vt#X^O&Z@dncC;tb1f5XqhTOH#dw6g={ zLL|COkA*i^vT{AacN=1*CNSoj@acx5*et0S3qvcF6q{c!qM-Vf{d`_rMECxv|3$%L z$o@!{^xy;JxrtL&N*~ZYEB#S^SFOA8O&v7-HC-}b-r_~ zVjSJ+izo*f-!ml^`~wbf%$wufXDr;BaGP_-d_n8qyMIx} zmypdFpOTzk=IzH(V0OwWb;IzDg{HeQ7|dmcQeAo*Uz9)B%nu3CP-Y7IFqav%I0h!9 zrIMfNeGBcsPwO3=@8;C2v5+rIcFuP*brSVOZy$3FG3(Li_3H^vGCrteEM%{}GMTx| z4yt1bb8eIWil-o2n_ zC4Ea~&hm)vefODf$;?@*6LuMXKnmeSC>ICS5}&gTzNTk=`*oJ*V(uPs&^YA{uZhPx(OGt#;^$&1 zioMO53i5NY3&quG_w&3r9M&@qwg!LaJ)2`oQI0IV&Sx=qkG%nca3kR!jVECB!u>4_jCX$E^%L+$ z_x2VB#si(wcpb>FA=JXiI7>^}4|d$t%fi4oIqn|ki|&@UKUDab4;hyWZV!DveUZL; z{F+dRZI%z2v#i?F3$AU;%+J-zq=tbW_fwv=u~!)UlRFdp5Z0a#gKW97icP^AVKB}! zCo*R_6A%h3Cgv2Ih1Ei#{!#Wxf>vT;FciNczpVt*I|fvoBN&K_?To_FIo<(f*n_)1=B_}dx$uS@lo|?I39OHvw$@x5DU#@2m+#8WoaBi$^_8ALz$Mu0$=W~&LL#Uo%AS_<a)V(i+S4@-sP)`bl-9F+s z?7O%ZJU{S`YoNYy^dJ~_E)Oz3-#Z90f5|5}=2Lh0_u&_=$@=wGp-}SO6NyQuj{~6e zv3G*cju`~&n&d;aDR!Wj_)ub%e5jqtV;c`9Ol$J^&iCEnV-^Qw&a!EC807BvQ|>f( zKp6bFG&3>>`AqkC>_c@X`L#);zr-X(`Xd)KVAhsx0QS{OXdkee~iNFD(DqjIo4&NoA$ z%1#Hi#}Ywd;NK}5uZgMK!=RQ+W{IU7_rm}qvdeg!M;J8R^j-Ra5*5RsTM4eQ33%de zh|1Xn$=UZ5huljnx)un=609Rk@3*z7wk>mZqjF!UQQSWEm;1u(DPeH?H@O#VGH(F9K4-%j2L(g6*?DQ7Kk#m+zTi1c z?hA*04T1q5bIADD$WU;*>cp{Oj;t91S*xWL*T{Ci=n@O}zd$MQT zqe}pMES?jYvv>{)g-K}{k-5pvvy|`kvPfP${5K5xcsmNNzj_d?Kb=Qx1`P;;w1t_G z`N(sM;X);IB6FPCA)(MM@TcU_kRD<1@~iAw|C`p_{4tBz@1WQokepla`8mPRJS?Z= zj&to$Sew}anajMVe5uwji{#N2+C!()UxmNaei;fuS@Ixrnf^|}FwECcY&NYN1hxE} zWW4F25C}h(3z@(4b{YsBe4GS39|?h!-?JifnY`D-zi{d)poaL^;G;M|n6B?{*t z|9HXNSD_GZa6PFE-TQ{Y{NdRI=i3qn0e`Vi+`wa82;9n)Td=Wv06cMKKe*w1TBmJ* zgWyx+!{96Voa?~ceIXFmZX-{skxjru#eDm8rcgiL7hUX))^0_eUg)qoOcgpx1*-wafWPf6t!Gqw^e6HK^ znCpHJEc497{=^5D!r=I=Y=WyU4g>Q`cBvJ6zlK8KrMxoUEv64F8!r6-Ud=iH{`pt# z0y}sH!KCSqeAhT3Y!H~c`MilZpkEj`x@8tzhU!@J{ka6UD?AXobj!x^gLSFa4T#Pz z*vp+hyQk*h*u!(lp>PQuq!wi%pHI_raeQLR!GSQfi<98Odqbdew%mf3Z5sfMRXpS%xPI?2cvUGg=ZHC$_Ru*~4$d9()TdBbx!*y?KatJkLiq%bo6#EvkIgMM z9lr-d&cB^FH_b6MLf{3}H?BoRJM@LV@$%Vc-uN5@+dk)z@dFW|u;rxG2eUTCQu$(% z@8-4H1K>alsTJmlwxN*WqHVl=a4`JYQ|ga7jq2O}EIG)}Ma**_L*W;#&s=8Oryxij zms`d^rv=09mQuS+XIf`(-7Lsl<{9PD_KXh5f0yY#hdyURb4tBBOSR=C{e~)YoQR|J z8R6@M%yITnt@u7QtJIDARHL$QbwuVk@$Ck|vyBeO9LGO63?@!@LgqN_B16EPa+7&Y zX3EV?Z=3|rqI{fNA_vvdg%I*Q6#UjX(R1fQg`f}^wlfF$KO7DvhC-fH2Z{}6Na#ZG zP~C|!Cf*JKudO-R2KyEag=vi)crI3(90osYI`W!0XXhXYy`7Dpg?T9^Js#u{ys=sk zeCzMPd&7Za=`*6c6Ytr4ydwnqP0!9}F?*Du&#WW4>_hX1X9(0EpPPMa_8^~oWhqCwK>w!0*wV0lJP2-7!5yj& z_YoXexGeN})kSctt?qDdb)ew32TQ`gJ8k$%{=yL2v9pZdSd|eRCEJOO5M1-Z`x!+vx3H{m^c$>mj&7|Gbd9a!&E_X=aCvDD;W+h2xj>PN;uGlm zrwcSV$NNdpz@s>HdnkK@KMxkQ);D# zV2f=X95DHJ$Qmrq!iM`?!0m^e(exSV0SV3IT-dQiSs47goY&kt*#QFD${BIuje>B$ zLR;>IAkMoiRP7un_~OTc&_nAYJY`R`JG}haUVQTNh6g;|(@Aj8Vjl2#Xjicbd*cQx zX7><|lN##+bI%0I_}7}nVJ7X9eY@*SQSd$8L-4y=E|Ac>HTj?3#|$nDX}Z5~oS4h5 zP-|_VjAuzH4ArLa+=h_+Q|Lw}-xN3(Rlz9>$;|q%vfRfIE!f~#Q zE(Ka=**|)Xc84DYWY5^y&jb9!WDi(sw+mcbA^XI_p(WskZJ+ec>UX%mLC%7a{aoPw zd7I6M!o^|VVVmEot)=g^`H0_eYxA;Dt&R8%uU#$(b?*CeZPYuCFAE8@CgXYMi-J#% z0Kut#c_CA|wp^d}8|3rK0WE0%+4a1Y%R-@4U%{G1#YXSo{V4&%3Xl5wvRlv9Jd z%DC~?4f>tvA>%b_yFg32JLWh?wBoRip2e{-@={Uy-bZWxtc1ct%EGYMz8ud`llD1q zKnuZ*{wxcdYxz_EkOZ6mc7;uq+KK(%Kgz;Vx>KI}czt*gCiy3!mI$nYwkEh<(szH$iJW%^mGbf&I0+al!g_L10+s<7Iubw z^SeqfwBU{#oLm$r{Y;m6B_P(d2is%i0%hRG0e^{~+99rxxS|`ckJ;+FL6@VQC6?yw zafhH@-DO)bob5w<;2z^z!2)oyG(R^9j|?jX zpCaV!SnNt6m^M+)j$YgHLAHqQvQD8XPO#!>SLrKeC%M7tu5w>kWRyEhC@S}b>wG-G zZ>8J|1`I3#t`}^0LxJK@hGLRAPX84};DznJu

`A$q9XDLQU2wy(5yqS&b&7YA{^7hg)sWT_Z)WC;1;J&U#G4toCLeu|vAftG zndk(U$NES=u!`16DcnhLxUUB^87nbwZd{cQPEGG294G&D7Z|Xmlk@|NN_xP|(_JJl z?ly9VBW-Lsa;S4@NT#ze4?6L8QFu|Ui|~|5aqcjEMi1dQIpSTQ=co3P3+E`#k0;5V zbvIh`Vn|o9U-#Y(?wk%3{Ju_ccz>*i*mtb!0%fZB3&*K=+m-%a(}mBXZ))fci(T7E zA5x)GS!i`5Q1GGE#UMjFTds}nSQ=VA2#|3{7iTCH6Ucp?emt!NwEs6i@I+T z@RthzxgY$Ly zEQ9-X+`-kQJ^6e-_+%{$eN#IM-qYO!7EbFf9H-;%GLWkZ*Dm5djZ4A%R2y!&;djWg zfc+c~rQAIrzDhgtTP%1}j!*mERq)!?^f^d1nQfjIaF*O;8_vyCs^>hO{I~>M>)D0* z0(>6k4uuzW75wp*8{EIto&4hk^#_%KUPd>`Wvt`|MUHW8sSLUMyTXU8e0Ddud9)Pt zUu?r^vrB-}T=s(-!aX;rGTvXX$0}C{_p#N1q4!II_Ao$df=dZ!IMST&!V8-Omxgjw zE12UL3roPyNU1Y8B6~@x75urwwPF&*65E6}C=SDv&6mFm!PI+Q`CQm;mm7rAoic74 z>I#cS1qjFS$X6OXAIaIVO~>D1$|KH^`PjnI1M=qe7yRLj^la06zqD?QFzS@%FUa91`6Is`8e=;ci}i4gUWz&99$Dav0sPM#&MfX@Pix_59scgOMczr0zPhm!f}4}F9kKo=ge_D$>&=O33o6H#4pjh+#N)p zm83T-JYRb@Zj#^w<)&)uA4Lhi{(PJ^r%R0B&`j;MCrfPO-zrtt?lc`M;|1%z@roZi zL~z6t!>e4;{({5$PxDgG()n3xT<7tbZ%46>?(1>iYky3n;Hj6&XbzR-S^Ce_t+du- zqh-AI)#2K$CN`TL%cHe{M+eKe&y>Hk=~?>;zBQA+FXF&!CSdV{^c^4@2F6WG@VOE& z#Vdz}f$^E$5j+zYlZ%$x=#LC zxp1JJpot^QWma@{9DR-FT{5hk&cBzF8 z2af8lbvYN!cMY*6n`=Mn^4)cS=U01b%bMHb}y{|?iJ2T1JUuBQ{UycEMcKJdpt&4`e*VE4o* zZEn1+7L7}ts&Y0#a<5T>so`3FidDKt++NmCd-Si|5l(v7 zLL2?j7JE%jXj-`ia$ng0P9x3NL+%t0r1jNKG>GBYFc&oKq($$S*fXEbj?pg8w$+5Y zx28&tP%N38BUjDI(o2-PAFdUr*yg?>qE;1cUs=wz?BZD9fQ znJb@Vux#*H%`uv5(R>I8Yf|MHI7)0JGu z=7S3fm|MMMKgYx8YE=I#*z(b*=SZ!fv(#tkxHejwLi=Q!wK=*s8l_dw!v67sds~9FFw>UHYrcePU4v~nX2LM-OB42k z8~ijoYe#;w;j{yO+BpaIgB$kvca-*FjSWw2I9OZfrRqSI4%#u=8~;tGa+R)HB(1|7 zXT<9OZ8p^k<}X`s`Dvf%^OQep`pj)3wSqC%ik8o0pZIZgOU+}ftyZjG?Wr9t%{4h5 zL(YxVYSNuD&Qv^1J3-IlzvC?Q@1Z47ZRGJsBN}PD969FaW8TA)w74koE!HbOR7?FS zeFAQGAE1>@vDwtTUQ-MGVH@|K?X684V6zWDSzo(A>+|1n`gH1{#iPUkp2-%bg$3Gb z&R_Q@Xj|wk%zgI6wb4fQiWXjDTp6aFr~1Z!)A{gfp!TSU#2$_~5~Lydod2f$>V2s8 zxmJwuntb=#Yt!jj%yC*cb=7i^&l$g3=cm>3h!$S+WcEnSbDs^jza6Um(>scD#4L4m zg0?1uKyScufx3-7s75^QlMFaW{_Xk`3 zsj^Sg7R;B=J~Q=FBW(%QH?B*@>%Q8ig_7^)xD4a9nFV5m%WU|~PkT?F>8wdBIku0c zQO#tI6Z3BiEg(hekJ;#6xK=2m)Ex8b$6(Em*5}@P#o0#MaM}-ZpYPqgwSrZpcA0rb z^wBm^z2d*)X?| z)>cmnOc|-Ip}gk5vBm1aT6xL^{yWa0Jb~Iyib>`*?~4xAdQ-eHesrw9=Dj{zI8M0p zV68u$i~o)@^FtSHAms)B9cSM8f!a2zhkWntdbiOI(_J&i34Rc&t)|%EzvI-q8mb+k zyJJ7^e%4n@pu6V3CUFfzaSfBWhM~9y z>ClE7iffp}H4McyOyU}b;uaHg_-*pc3j57%w-Ha?qgx*K8EV^ zb?WmC#RYWY0*31OfqH&J@d6-TVAydJL-7kBeqktn0mLs1#YZ&aBZeKvF%<6r;vI$^ zS27fr0pc>&`pjPp#eI;tkD+*zLA=SD%RI&Pg`xNbQ14_YegVWU48=`=xQU^-2@p3i6qffHK zaUVl*B_yt7D6WLWl?=tRka(7%coq^zFci;1;#r2`XhLCr)i|W*iiVwNJVjrshQ>XsZP(7+nJ*uJlSe^PMO857gTm ziX#AV1VeEIAdaANAwhCM_4z=3zM*&r5brP)*8t)ghTW}iaUw%;BBZ{{P<#rBPZ^3sA#o@}aVsQlWhjn@#L*1J(U3Tr%Gm_T zS;Ya7IG~}p9un6x6xT!IdWPbLNZim++z^Qy8j9Z`@jF9tOeBtJD2|E5F%88@kvOTL zcq@P<-DczHg{LL8m^!P`!jsy@a8937vWg zL-iXv^&5ujLv-px4Ar0L)SnotZ_%l5F;xGfQ~zVA{zs?&$54HaPJND{`X8P8A4By; zI`u_{>Z5e(qYTww>C|5ts_)XN?=n=MM&E;*V5mM#r#{V4eVR^vnxT3;oq9Y&^>{k< zc!uf&f%-s0^@>2fqM>?7pdQjteIrocXsA9DsLwQ1FG`xnVTS5mfqGX%^`$_4siFE< zpgz`6eJoHPYpA{#sP8pY&kWQv8>&wR>XQxCKLhp8hU%GtdS*lQ