From 624b862076b5ddb460d4d95dcedeee0c84a21e29 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Fri, 13 Feb 2015 18:59:30 +0200 Subject: [PATCH 01/29] Commit because I have to go home, still fixing PickupSequence --- .../frc/team3316/robot/config/Config.java | 8 ++ .../frc/team3316/robot/humanIO/SDB.java | 2 +- .../robot/rollerGripper/commands/RollIn.java | 6 +- .../robot/sequences/AddGamePieceSequence.java | 20 +++++ .../robot/sequences/PickupSequence.java | 37 ++++++++ .../robot/sequences/pickupSequence.java | 25 +++--- .../team3316/robot/stacker/GamePieceType.java | 2 +- .../stacker/commands/AddGamePieceToStack.java | 40 +++++++++ .../robot/stacker/commands/MoveStacker.java | 26 +----- .../stacker/commands/MoveStackerToFloor.java | 14 ++- .../stacker/commands/MoveStackerToTote.java | 3 +- .../robot/subsystems/RollerGripper.java | 88 ++++++++++++++++--- 12 files changed, 210 insertions(+), 61 deletions(-) create mode 100644 src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java create mode 100644 src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java create mode 100644 src/org/usfirst/frc/team3316/robot/stacker/commands/AddGamePieceToStack.java diff --git a/src/org/usfirst/frc/team3316/robot/config/Config.java b/src/org/usfirst/frc/team3316/robot/config/Config.java index f5ce0ff..307d44b 100644 --- a/src/org/usfirst/frc/team3316/robot/config/Config.java +++ b/src/org/usfirst/frc/team3316/robot/config/Config.java @@ -239,6 +239,14 @@ private void initConfig () addToVariables("rollerGripper_LeftScale", 1.0); addToVariables("rollerGripper_RightScale", -1.0); + addToVariables("rollerGripper_ToteDistanceMinimum", 0.325); + addToVariables("rollerGripper_ToteDistanceMaximum", 0.34); + + addToVariables("rollerGripper_ContainerDistanceMinimum", 0.39); + addToVariables("rollerGripper_ContainerDistanceMaximum", 0.41); + + addToVariables("rollerGripper_GamePieceDistanceThreshold", 1.0); + //RollIn addToVariables("rollerGripper_RollIn_SpeedLeft", 1.0); addToVariables("rollerGripper_RollIn_SpeedRight", 1.0); diff --git a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java index b74751e..33fcea5 100644 --- a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java +++ b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java @@ -44,7 +44,7 @@ public void run () put ("Left Ratchet", Robot.stacker.getSwitchLeft()); put ("Right Ratchet", Robot.stacker.getSwitchRight()); - put ("Game Piece Switch", Robot.rollerGripper.getSwitchGP()); + put ("Game Piece Switch", Robot.rollerGripper.getSwitchGamePiece()); } private void put (String name, double d) diff --git a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollIn.java b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollIn.java index 0edd856..351456b 100644 --- a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollIn.java +++ b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollIn.java @@ -1,5 +1,6 @@ package org.usfirst.frc.team3316.robot.rollerGripper.commands; +import org.usfirst.frc.team3316.robot.Robot; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; public class RollIn extends Roll @@ -17,5 +18,8 @@ protected void setSpeeds() } } - //TODO: add isFinished by switch and IR + protected boolean isFinished () + { + return Robot.rollerGripper.getSwitchGamePiece(); + } } diff --git a/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java new file mode 100644 index 0000000..f7e1c78 --- /dev/null +++ b/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java @@ -0,0 +1,20 @@ +package org.usfirst.frc.team3316.robot.sequences; + +import org.usfirst.frc.team3316.robot.stacker.commands.AddGamePieceToStack; +import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToFloor; +import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToTote; + +import edu.wpi.first.wpilibj.command.CommandGroup; + +/** + * + */ +public class AddGamePieceSequence extends CommandGroup +{ + public AddGamePieceSequence() + { + addSequential(new MoveStackerToFloor()); + addSequential(new AddGamePieceToStack()); + addSequential(new MoveStackerToTote()); + } +} diff --git a/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java new file mode 100644 index 0000000..f17f047 --- /dev/null +++ b/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java @@ -0,0 +1,37 @@ +package org.usfirst.frc.team3316.robot.sequences; + +import org.usfirst.frc.team3316.robot.Robot; +import org.usfirst.frc.team3316.robot.config.Config; +import org.usfirst.frc.team3316.robot.logger.DBugLogger; +import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollIn; +import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToFloor; +import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToTote; + +import edu.wpi.first.wpilibj.command.CommandGroup; + +/** + * + */ +public class PickupSequence extends CommandGroup +{ + DBugLogger logger = Robot.logger; + Config config = Robot.config; + + AddGamePieceSequence addGamePieceSequence; + + public PickupSequence () + { + addSequential(new MoveStackerToTote()); + addSequential(new RollIn()); + + addGamePieceSequence = new AddGamePieceSequence(); + } + + protected void end () + { + if (!Robot.stacker.isFull() && Robot.rollerGripper.getSwitchGamePiece()) + { + addGamePieceSequence.start(); + } + } +} diff --git a/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java index f1373d5..f17f047 100644 --- a/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java +++ b/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java @@ -12,23 +12,26 @@ /** * */ -public class pickupSequence extends CommandGroup +public class PickupSequence extends CommandGroup { DBugLogger logger = Robot.logger; Config config = Robot.config; - protected void initialize() + AddGamePieceSequence addGamePieceSequence; + + public PickupSequence () + { + addSequential(new MoveStackerToTote()); + addSequential(new RollIn()); + + addGamePieceSequence = new AddGamePieceSequence(); + } + + protected void end () { - if (Robot.stacker.isFull()) + if (!Robot.stacker.isFull() && Robot.rollerGripper.getSwitchGamePiece()) { - this.cancel(); + addGamePieceSequence.start(); } } - public pickupSequence() - { - addSequential(new MoveStackerToTote()); //makes sure the new gamepiece can enter - addSequential(new RollIn()); - addSequential(new MoveStackerToFloor()); - addSequential(new MoveStackerToTote()); - } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/GamePieceType.java b/src/org/usfirst/frc/team3316/robot/stacker/GamePieceType.java index 1e937f2..64af068 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/GamePieceType.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/GamePieceType.java @@ -3,5 +3,5 @@ public enum GamePieceType { - Container, GreyTote, YellowTote; + Container, Tote; } \ No newline at end of file diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/AddGamePieceToStack.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/AddGamePieceToStack.java new file mode 100644 index 0000000..b640081 --- /dev/null +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/AddGamePieceToStack.java @@ -0,0 +1,40 @@ +package org.usfirst.frc.team3316.robot.stacker.commands; + +import org.usfirst.frc.team3316.robot.Robot; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; +import org.usfirst.frc.team3316.robot.stacker.GamePiece; +import org.usfirst.frc.team3316.robot.stacker.GamePieceType; + +import edu.wpi.first.wpilibj.command.Command; + +/** + * + */ +public class AddGamePieceToStack extends Command +{ + public AddGamePieceToStack() {} + + protected void initialize() + { + GamePieceCollected gpCollected = Robot.rollerGripper.getGamePieceCollected(); + if (gpCollected == GamePieceCollected.Container) + { + Robot.stacker.pushToStack(new GamePiece(GamePieceType.Container)); + } + else if (gpCollected == GamePieceCollected.Tote) + { + Robot.stacker.pushToStack(new GamePiece(GamePieceType.Tote)); + } + } + + protected void execute() {} + + protected boolean isFinished() + { + return true; + } + + protected void end() {} + + protected void interrupted() {} +} diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java index 37007f6..d62cca9 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java @@ -15,15 +15,9 @@ public abstract class MoveStacker extends Command DBugLogger logger = Robot.logger; Config config = Robot.config; - protected double heightMin, heightMax; - - String heightMaxName = "", heightMinName = ""; - - public MoveStacker(String heightMaxName, String heightMinName) + public MoveStacker() { requires(Robot.stacker); - this.heightMaxName = heightMaxName; - this.heightMinName = heightMinName; } protected void initialize() @@ -36,11 +30,6 @@ protected void execute() {} protected boolean isFinished() { return true; - /* - updateHeightRange(); - double currentHeight = Robot.stacker.getHeight(); - return (currentHeight > heightMin) && (currentHeight < heightMax); - */ } protected void end() {} @@ -48,17 +37,4 @@ protected void end() {} protected void interrupted() {} protected abstract void setSolenoids(); - - protected void updateHeightRange () - { - try - { - heightMax = (double) config.get(heightMaxName); - heightMin = (double) config.get(heightMinName); - } - catch (ConfigException e) - { - logger.severe(e); - } - } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java index 4744a66..2eb2343 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java @@ -2,6 +2,7 @@ import org.usfirst.frc.team3316.robot.Robot; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; /** * @@ -9,23 +10,18 @@ public class MoveStackerToFloor extends MoveStacker { double gpDistanceMin, gpDistanceMax; - - public MoveStackerToFloor() - { - super("STACKER_MOVE_STACKER_TO_FLOOR_HEIGHT_MAX", - "STACKER_MOVE_STACKER_TO_FLOOR_HEIGHT_MIN"); - } protected void setSolenoids() { - Robot.stacker.openSolenoidGripper(); //This line is strategically problematic and should be solved - //need to insert condition 'only if there is no gp below the stack' + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.None) + { + Robot.stacker.openSolenoidGripper(); + } Robot.stacker.closeSolenoidContainer(); Robot.stacker.openSolenoidUpper(); Robot.stacker.openSolenoidBottom(); } - //TODO: implement this method in setSolenoids() private void updateDistanceRange () { try diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java index b014f29..6a566e3 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java @@ -10,8 +10,7 @@ public class MoveStackerToTote extends MoveStacker { public MoveStackerToTote() { - super("STACKER_MOVE_STACKER_TO_TOTE_HEIGHT_MAX", - "STACKER_MOVE_STACKER_TO_TOTE_HEIGHT_MIN"); + super(); } protected void initialize() diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java b/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java index 2b40d79..ff0b28c 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java @@ -30,6 +30,14 @@ public class RollerGripper extends Subsystem private double leftScale, rightScale; + // Variables for getGamePieceCollected() + // They are set in updateDistanceVariables() + private double toteDistanceMin, + toteDistanceMax, + containerDistanceMin, + containerDistanceMax, + gpDistanceThreshold; + private Roll defaultRoll; public RollerGripper () @@ -56,6 +64,75 @@ public boolean set (double speedLeft, double speedRight) return true; } + //TODO: fix name to be getIRGPDistance + public double getGPIRDistance () + { + return (1 / gripperGPIR.getVoltage()); + } + + public boolean getSwitchGamePiece () + { + return !gripperSwitchGP.get(); + } + + /** + * Returns which gamepiece there is in the roller gripper (if any) + * @return Tote for tote, Container for container, Unsure if there + * is something in but can't figure out which and none if empty + */ + public GamePieceCollected getGamePieceCollected () + { + updateDistanceVariables(); + + double gpDistance = getGPIRDistance(); + boolean gpSwitch = getSwitchGamePiece(); + + if (gpSwitch) + { + if (gpDistance > toteDistanceMin && gpDistance < toteDistanceMax) + { + return GamePieceCollected.Tote; + } + else if (gpDistance > containerDistanceMin && gpDistance < containerDistanceMax) + { + return GamePieceCollected.Container; + } + else + { + return GamePieceCollected.Unsure; + } + } + else + { + if (gpDistance < gpDistanceThreshold) + { + return GamePieceCollected.Unsure; + } + else + { + return GamePieceCollected.None; + } + } + } + + private void updateDistanceVariables () + { + try + { + toteDistanceMin = (double) config.get("rollerGripper_ToteDistanceMinimum"); + toteDistanceMax = (double) config.get("rollerGripper_ToteDistanceMaximum"); + + containerDistanceMin = (double) config.get("rollerGripper_ContainerDistanceMinimum"); + containerDistanceMax = (double) config.get("rollerGripper_ContainerDistanceMaximum"); + + gpDistanceThreshold = (double) config.get("rollerGripper_GamePieceDistanceThreshold"); + } + catch (ConfigException e) + { + logger.severe(e); + } + } + private void updateScales () { try @@ -69,17 +146,6 @@ private void updateScales () } } - //TODO: fix name to be getIRGPDistance - public double getGPIRDistance () - { - return (1 / gripperGPIR.getVoltage()); - } - - public boolean getSwitchGP () - { - return !gripperSwitchGP.get(); - } - private void printTheTruth() { System.out.println("Vita is the Melech!!"); From b6e2f23ef2ad387d8552bd086e7f717280d49f09 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Sat, 14 Feb 2015 13:56:57 +0200 Subject: [PATCH 02/29] Finished adding PickupSequence and fixed MoveStacker commmands --- .../frc/team3316/robot/config/Config.java | 35 ++++++------ .../robot/rollerGripper/commands/RollOut.java | 7 +++ .../robot/sequences/AddGamePieceSequence.java | 2 +- .../robot/sequences/pickupSequence.java | 37 ------------- .../robot/stacker/StackerPosition.java | 2 +- .../stacker/commands/MoveStackerToFloor.java | 13 +++-- .../stacker/commands/MoveStackerToStep.java | 30 +++++++---- .../stacker/commands/MoveStackerToTote.java | 18 +++---- .../team3316/robot/subsystems/Stacker.java | 53 ++++++++++++++++--- 9 files changed, 108 insertions(+), 89 deletions(-) delete mode 100644 src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java diff --git a/src/org/usfirst/frc/team3316/robot/config/Config.java b/src/org/usfirst/frc/team3316/robot/config/Config.java index 307d44b..4d4b9f1 100644 --- a/src/org/usfirst/frc/team3316/robot/config/Config.java +++ b/src/org/usfirst/frc/team3316/robot/config/Config.java @@ -152,9 +152,9 @@ private void initConfig () addToConstants("CHASSIS_ENCODER_CENTER_A", 0); addToConstants("CHASSIS_ENCODER_CENTER_B", 1); - addToConstants("CHASSIS_ENCODER_LEFT_DISTANCE_PER_PULSE", -0.07363107781851077902646820429561); - addToConstants("CHASSIS_ENCODER_RIGHT_DISTANCE_PER_PULSE", 0.07363107781851077902646820429561); - addToConstants("CHASSIS_ENCODER_CENTER_DISTANCE_PER_PULSE", 0.02454369260617025967548940143187); + addToConstants("CHASSIS_ENCODER_LEFT_DISTANCE_PER_PULSE", -0.0018702293765902); + addToConstants("CHASSIS_ENCODER_RIGHT_DISTANCE_PER_PULSE", 0.0018702293765902); + addToConstants("CHASSIS_ENCODER_CENTER_DISTANCE_PER_PULSE", 0.0012468195843934); addToConstants("CHASSIS_WIDTH", 0.5322); //in meters /* @@ -270,7 +270,7 @@ private void initConfig () addToVariables("rollerGripper_RollJoystick_InvertX", true); addToVariables("rollerGripper_RollJoystick_InvertY", false); - addToVariables("rollerGripper_RollJoystick_LowPass", 0.05); + addToVariables("rollerGripper_RollJoystick_LowPass", 0.15); /* * Stacker @@ -293,21 +293,26 @@ private void initConfig () addToConstants("STACKER_IR", 0); + + addToConstants("SWITCH_RATCHET_LEFT", 7); addToConstants("SWITCH_RATCHET_RIGHT", 8); - addToConstants("SWITCH_RATCHET_LEFT", 9); /* * Variables */ - //MoveStacker - //MoveStackerToFloor - addToVariables("stacker_MoveStackerToFloor_HeightMax", 0.4); - addToVariables("stacker_MoveStackerToFloor_HeightMin", 0.42); - //MoveStackerToStep - addToVariables("stacker_MoveStackerToStep_HeightMax", 1.05); - addToVariables("stacker_MoveStackerToStep_HeightMin", 0.95); - //MoveStackerToTote - addToVariables("stacker_MoveStackerToTote_HeightMax", 1.62); - addToVariables("stacker_MoveStackerToTote_HeightMin", 1.45); + //Subsystem + + //TODO: re-determine these values + addToVariables("stacker_HeightFloorMinimum", 0.4); + addToVariables("stacker_HeightFloorMaximum", 0.42); + + addToVariables("stacker_HeightToteMinimum", 1.45); + addToVariables("stacker_HeightToteMaximum", 1.62); + + addToVariables("stacker_HeightStepMinimum", 0.95); + addToVariables("stacker_HeightStepMaximum", 1.05); + + addToVariables("stacker_HeightStuckOnContainerMinimum", 1.05); + addToVariables("stacker_HeightStuckOnContainerMaximum", 1.05); } } diff --git a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java index 2952d45..d63ec41 100644 --- a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java +++ b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java @@ -1,6 +1,8 @@ package org.usfirst.frc.team3316.robot.rollerGripper.commands; +import org.usfirst.frc.team3316.robot.Robot; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; public class RollOut extends Roll { @@ -16,4 +18,9 @@ protected void setSpeeds () logger.severe(e); } } + + protected boolean isFinished () + { + return Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.None; + } } diff --git a/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java index f7e1c78..2b6fb26 100644 --- a/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java +++ b/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java @@ -13,8 +13,8 @@ public class AddGamePieceSequence extends CommandGroup { public AddGamePieceSequence() { + addSequential(new AddGamePieceToStack()); addSequential(new MoveStackerToFloor()); - addSequential(new AddGamePieceToStack()); addSequential(new MoveStackerToTote()); } } diff --git a/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java deleted file mode 100644 index f17f047..0000000 --- a/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java +++ /dev/null @@ -1,37 +0,0 @@ -package org.usfirst.frc.team3316.robot.sequences; - -import org.usfirst.frc.team3316.robot.Robot; -import org.usfirst.frc.team3316.robot.config.Config; -import org.usfirst.frc.team3316.robot.logger.DBugLogger; -import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollIn; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToFloor; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToTote; - -import edu.wpi.first.wpilibj.command.CommandGroup; - -/** - * - */ -public class PickupSequence extends CommandGroup -{ - DBugLogger logger = Robot.logger; - Config config = Robot.config; - - AddGamePieceSequence addGamePieceSequence; - - public PickupSequence () - { - addSequential(new MoveStackerToTote()); - addSequential(new RollIn()); - - addGamePieceSequence = new AddGamePieceSequence(); - } - - protected void end () - { - if (!Robot.stacker.isFull() && Robot.rollerGripper.getSwitchGamePiece()) - { - addGamePieceSequence.start(); - } - } -} diff --git a/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java b/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java index e7867c1..4ae1df1 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java @@ -2,5 +2,5 @@ public enum StackerPosition { - Tote, Step, Floor; + Tote, Step, Floor, StuckOnContainer; } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java index 2eb2343..98bad13 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java @@ -3,13 +3,13 @@ import org.usfirst.frc.team3316.robot.Robot; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; +import org.usfirst.frc.team3316.robot.stacker.StackerPosition; /** * */ public class MoveStackerToFloor extends MoveStacker { - double gpDistanceMin, gpDistanceMax; protected void setSolenoids() { @@ -22,16 +22,15 @@ protected void setSolenoids() Robot.stacker.openSolenoidBottom(); } - private void updateDistanceRange () + protected boolean isFinished () { - try + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) { - gpDistanceMax = (double) config.get("stacker_MoveStackerToFloor_GPDistanceMax"); - gpDistanceMin = (double) config.get("stacker_MoveStackerToFloor_GPDistanceMin"); + return (Robot.stacker.getPosition() == StackerPosition.StuckOnContainer); } - catch (ConfigException e) + else { - logger.severe(e); + return (Robot.stacker.getPosition() == StackerPosition.Floor); } } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java index c806f29..adcaf7d 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java @@ -1,28 +1,19 @@ package org.usfirst.frc.team3316.robot.stacker.commands; import org.usfirst.frc.team3316.robot.Robot; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.stacker.StackerPosition; import edu.wpi.first.wpilibj.DoubleSolenoid; -/** - * - */ public class MoveStackerToStep extends MoveStacker { - public MoveStackerToStep() - { - super("STACKER_MOVE_STACKER_TO_STEP_HEIGHT_MAX", - "STACKER_MOVE_STACKER_TO_STEP_HEIGHT_MIN"); - } - protected void initialize() { /* * If one of the ratchets is not in place and they should be pressed, dont start */ - if ( Robot.stacker.getSolenoidContainer() == DoubleSolenoid.Value.kReverse && - Robot.stacker.getPosition() == StackerPosition.Floor && + if ( Robot.stacker.getPosition() == StackerPosition.Floor && (!Robot.stacker.getSwitchLeft() || !Robot.stacker.getSwitchRight())) { this.cancel(); @@ -35,7 +26,24 @@ protected void initialize() protected void setSolenoids() { + //TODO: check if the condition should be if the command started when the stacker was stuck on a container + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) + { + Robot.stacker.openSolenoidContainer(); + } Robot.stacker.closeSolenoidUpper(); Robot.stacker.openSolenoidBottom(); } + + protected boolean isFinished () + { + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) + { + return (Robot.stacker.getPosition() == StackerPosition.StuckOnContainer); + } + else + { + return (Robot.stacker.getPosition() == StackerPosition.Step); + } + } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java index 6a566e3..a8ef7e6 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java @@ -1,6 +1,7 @@ package org.usfirst.frc.team3316.robot.stacker.commands; import org.usfirst.frc.team3316.robot.Robot; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.stacker.GamePieceType; import org.usfirst.frc.team3316.robot.stacker.StackerPosition; @@ -8,18 +9,12 @@ public class MoveStackerToTote extends MoveStacker { - public MoveStackerToTote() - { - super(); - } - protected void initialize() { /* * If one of the ratchets is not in place and they should be pressed, dont start */ - if ( Robot.stacker.getSolenoidContainer() == DoubleSolenoid.Value.kReverse && - Robot.stacker.getPosition() == StackerPosition.Floor && + if ( Robot.stacker.getPosition() == StackerPosition.Floor && (!Robot.stacker.getSwitchLeft() || !Robot.stacker.getSwitchRight())) { this.cancel(); @@ -32,12 +27,17 @@ protected void initialize() protected void setSolenoids() { - if ( Robot.stacker.getStackBase() != null && - Robot.stacker.getStackBase().getType() == GamePieceType.Container) + //TODO: check if the condition should be if the command started when the stacker was stuck on a container + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) { Robot.stacker.openSolenoidContainer(); } Robot.stacker.closeSolenoidUpper(); Robot.stacker.closeSolenoidBottom(); } + + protected boolean isFinished () + { + return (Robot.stacker.getPosition() == StackerPosition.Tote); + } } diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java index ec1b36d..fcdbe36 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java @@ -32,6 +32,11 @@ public class Stacker extends Subsystem private AnalogInput heightIR; //infrared private DigitalInput switchRight, switchLeft; //the switches that signify if there's a tote or a container in the stacker + private double heightFloorMin, heightFloorMax, + heightStepMin, heightStepMax, + heightToteMin, heightToteMax, + heightStuckOnContainerMin, heightStuckOnContainerMax; + private Stack stack; public Stacker () @@ -125,25 +130,57 @@ public boolean getSwitchLeft () return switchLeft.get(); } + /* + * TODO: check if StuckOnContainer is necessary (if it's not simply step or floor) + */ public StackerPosition getPosition () { - /* - * TODO: this method should return a position based on the stacker IR - */ - if (solenoidUpper.get() == DoubleSolenoid.Value.kForward && - solenoidBottom.get() == DoubleSolenoid.Value.kForward) + updateHeights(); + + double height = getHeight(); + + if ((height > heightFloorMin) && (height < heightFloorMax)) { return StackerPosition.Floor; } - else if (solenoidUpper.get() == DoubleSolenoid.Value.kReverse && - solenoidBottom.get() == DoubleSolenoid.Value.kReverse) + else if ((height > heightToteMin) && (height < heightToteMax)) { return StackerPosition.Tote; } - else + else if ((height > heightStepMin) && (height < heightStepMax)) { return StackerPosition.Step; } + else if ((height > heightStuckOnContainerMin) && (height < heightStuckOnContainerMax)) + { + return StackerPosition.StuckOnContainer; + } + else + { + return null; + } + } + + private void updateHeights () + { + try + { + heightFloorMin = (double) config.get("stacker_HeightFloorMinimum"); + heightFloorMax = (double) config.get("stacker_HeightFloorMaximum"); + + heightToteMin = (double) config.get("stacker_HeightToteMinimum"); + heightToteMax = (double) config.get("stacker_HeightToteMaximum"); + + heightStepMin = (double) config.get("stacker_HeightStepMinimum"); + heightStepMax = (double) config.get("stacker_HeightStepMaximum"); + + heightStuckOnContainerMin = (double) config.get("stacker_HeightStuckOnContainerMinimum"); + heightStuckOnContainerMax = (double) config.get("stacker_HeightStuckOnContainerMaximum"); + } + catch (ConfigException e) + { + logger.severe(e); + } } public DoubleSolenoid.Value getSolenoidContainer () From aa551ba96b22a6fdaf1e98d77ec5fd0c497f8f9a Mon Sep 17 00:00:00 2001 From: frc3316 Date: Sat, 14 Feb 2015 13:56:57 +0200 Subject: [PATCH 03/29] Finished adding PickupSequence and fixed MoveStacker commmands --- .../frc/team3316/robot/config/Config.java | 36 +++++++------ .../frc/team3316/robot/humanIO/SDB.java | 15 ++++++ .../robot/rollerGripper/commands/RollOut.java | 7 +++ .../robot/sequences/AddGamePieceSequence.java | 2 +- .../robot/sequences/pickupSequence.java | 37 ------------- .../robot/stacker/StackerPosition.java | 2 +- .../stacker/commands/MoveStackerToFloor.java | 13 +++-- .../stacker/commands/MoveStackerToStep.java | 30 +++++++---- .../stacker/commands/MoveStackerToTote.java | 18 +++---- .../team3316/robot/subsystems/Stacker.java | 53 ++++++++++++++++--- 10 files changed, 123 insertions(+), 90 deletions(-) delete mode 100644 src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java diff --git a/src/org/usfirst/frc/team3316/robot/config/Config.java b/src/org/usfirst/frc/team3316/robot/config/Config.java index 307d44b..e037fb0 100644 --- a/src/org/usfirst/frc/team3316/robot/config/Config.java +++ b/src/org/usfirst/frc/team3316/robot/config/Config.java @@ -152,9 +152,9 @@ private void initConfig () addToConstants("CHASSIS_ENCODER_CENTER_A", 0); addToConstants("CHASSIS_ENCODER_CENTER_B", 1); - addToConstants("CHASSIS_ENCODER_LEFT_DISTANCE_PER_PULSE", -0.07363107781851077902646820429561); - addToConstants("CHASSIS_ENCODER_RIGHT_DISTANCE_PER_PULSE", 0.07363107781851077902646820429561); - addToConstants("CHASSIS_ENCODER_CENTER_DISTANCE_PER_PULSE", 0.02454369260617025967548940143187); + addToConstants("CHASSIS_ENCODER_LEFT_DISTANCE_PER_PULSE", -0.0018702293765902); + addToConstants("CHASSIS_ENCODER_RIGHT_DISTANCE_PER_PULSE", 0.0018702293765902); + addToConstants("CHASSIS_ENCODER_CENTER_DISTANCE_PER_PULSE", 0.0012468195843934); addToConstants("CHASSIS_WIDTH", 0.5322); //in meters /* @@ -270,7 +270,7 @@ private void initConfig () addToVariables("rollerGripper_RollJoystick_InvertX", true); addToVariables("rollerGripper_RollJoystick_InvertY", false); - addToVariables("rollerGripper_RollJoystick_LowPass", 0.05); + addToVariables("rollerGripper_RollJoystick_LowPass", 0.15); /* * Stacker @@ -293,21 +293,25 @@ private void initConfig () addToConstants("STACKER_IR", 0); + + addToConstants("SWITCH_RATCHET_LEFT", 7); addToConstants("SWITCH_RATCHET_RIGHT", 8); - addToConstants("SWITCH_RATCHET_LEFT", 9); - /* * Variables */ - //MoveStacker - //MoveStackerToFloor - addToVariables("stacker_MoveStackerToFloor_HeightMax", 0.4); - addToVariables("stacker_MoveStackerToFloor_HeightMin", 0.42); - //MoveStackerToStep - addToVariables("stacker_MoveStackerToStep_HeightMax", 1.05); - addToVariables("stacker_MoveStackerToStep_HeightMin", 0.95); - //MoveStackerToTote - addToVariables("stacker_MoveStackerToTote_HeightMax", 1.62); - addToVariables("stacker_MoveStackerToTote_HeightMin", 1.45); + //Subsystem + + //TODO: re-determine these values + addToVariables("stacker_HeightFloorMinimum", 0.4); + addToVariables("stacker_HeightFloorMaximum", 0.42); + + addToVariables("stacker_HeightToteMinimum", 1.45); + addToVariables("stacker_HeightToteMaximum", 1.62); + + addToVariables("stacker_HeightStepMinimum", 0.95); + addToVariables("stacker_HeightStepMaximum", 1.05); + + addToVariables("stacker_HeightStuckOnContainerMinimum", 1.05); + addToVariables("stacker_HeightStuckOnContainerMaximum", 1.05); } } diff --git a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java index 33fcea5..c0fc1d7 100644 --- a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java +++ b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java @@ -163,5 +163,20 @@ private void initSDB () putConfigVariableInSDB("rollerGripper_RollJoystick_LowPass"); + /* + * Stacker + */ + putConfigVariableInSDB("stacker_HeightFloorMinimum"); + putConfigVariableInSDB("stacker_HeightFloorMaximum"); + + putConfigVariableInSDB("stacker_HeightToteMinimum"); + putConfigVariableInSDB("stacker_HeightToteMaximum"); + + putConfigVariableInSDB("stacker_HeightStepMinimum"); + putConfigVariableInSDB("stacker_HeightStepMaximum"); + + putConfigVariableInSDB("stacker_HeightStuckOnContainerMinimum"); + putConfigVariableInSDB("stacker_HeightStuckOnContainerMaximum"); + } } \ No newline at end of file diff --git a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java index 2952d45..d63ec41 100644 --- a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java +++ b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java @@ -1,6 +1,8 @@ package org.usfirst.frc.team3316.robot.rollerGripper.commands; +import org.usfirst.frc.team3316.robot.Robot; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; public class RollOut extends Roll { @@ -16,4 +18,9 @@ protected void setSpeeds () logger.severe(e); } } + + protected boolean isFinished () + { + return Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.None; + } } diff --git a/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java index f7e1c78..2b6fb26 100644 --- a/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java +++ b/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java @@ -13,8 +13,8 @@ public class AddGamePieceSequence extends CommandGroup { public AddGamePieceSequence() { + addSequential(new AddGamePieceToStack()); addSequential(new MoveStackerToFloor()); - addSequential(new AddGamePieceToStack()); addSequential(new MoveStackerToTote()); } } diff --git a/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java deleted file mode 100644 index f17f047..0000000 --- a/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java +++ /dev/null @@ -1,37 +0,0 @@ -package org.usfirst.frc.team3316.robot.sequences; - -import org.usfirst.frc.team3316.robot.Robot; -import org.usfirst.frc.team3316.robot.config.Config; -import org.usfirst.frc.team3316.robot.logger.DBugLogger; -import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollIn; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToFloor; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToTote; - -import edu.wpi.first.wpilibj.command.CommandGroup; - -/** - * - */ -public class PickupSequence extends CommandGroup -{ - DBugLogger logger = Robot.logger; - Config config = Robot.config; - - AddGamePieceSequence addGamePieceSequence; - - public PickupSequence () - { - addSequential(new MoveStackerToTote()); - addSequential(new RollIn()); - - addGamePieceSequence = new AddGamePieceSequence(); - } - - protected void end () - { - if (!Robot.stacker.isFull() && Robot.rollerGripper.getSwitchGamePiece()) - { - addGamePieceSequence.start(); - } - } -} diff --git a/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java b/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java index e7867c1..4ae1df1 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java @@ -2,5 +2,5 @@ public enum StackerPosition { - Tote, Step, Floor; + Tote, Step, Floor, StuckOnContainer; } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java index 2eb2343..98bad13 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java @@ -3,13 +3,13 @@ import org.usfirst.frc.team3316.robot.Robot; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; +import org.usfirst.frc.team3316.robot.stacker.StackerPosition; /** * */ public class MoveStackerToFloor extends MoveStacker { - double gpDistanceMin, gpDistanceMax; protected void setSolenoids() { @@ -22,16 +22,15 @@ protected void setSolenoids() Robot.stacker.openSolenoidBottom(); } - private void updateDistanceRange () + protected boolean isFinished () { - try + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) { - gpDistanceMax = (double) config.get("stacker_MoveStackerToFloor_GPDistanceMax"); - gpDistanceMin = (double) config.get("stacker_MoveStackerToFloor_GPDistanceMin"); + return (Robot.stacker.getPosition() == StackerPosition.StuckOnContainer); } - catch (ConfigException e) + else { - logger.severe(e); + return (Robot.stacker.getPosition() == StackerPosition.Floor); } } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java index c806f29..adcaf7d 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java @@ -1,28 +1,19 @@ package org.usfirst.frc.team3316.robot.stacker.commands; import org.usfirst.frc.team3316.robot.Robot; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.stacker.StackerPosition; import edu.wpi.first.wpilibj.DoubleSolenoid; -/** - * - */ public class MoveStackerToStep extends MoveStacker { - public MoveStackerToStep() - { - super("STACKER_MOVE_STACKER_TO_STEP_HEIGHT_MAX", - "STACKER_MOVE_STACKER_TO_STEP_HEIGHT_MIN"); - } - protected void initialize() { /* * If one of the ratchets is not in place and they should be pressed, dont start */ - if ( Robot.stacker.getSolenoidContainer() == DoubleSolenoid.Value.kReverse && - Robot.stacker.getPosition() == StackerPosition.Floor && + if ( Robot.stacker.getPosition() == StackerPosition.Floor && (!Robot.stacker.getSwitchLeft() || !Robot.stacker.getSwitchRight())) { this.cancel(); @@ -35,7 +26,24 @@ protected void initialize() protected void setSolenoids() { + //TODO: check if the condition should be if the command started when the stacker was stuck on a container + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) + { + Robot.stacker.openSolenoidContainer(); + } Robot.stacker.closeSolenoidUpper(); Robot.stacker.openSolenoidBottom(); } + + protected boolean isFinished () + { + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) + { + return (Robot.stacker.getPosition() == StackerPosition.StuckOnContainer); + } + else + { + return (Robot.stacker.getPosition() == StackerPosition.Step); + } + } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java index 6a566e3..a8ef7e6 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java @@ -1,6 +1,7 @@ package org.usfirst.frc.team3316.robot.stacker.commands; import org.usfirst.frc.team3316.robot.Robot; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.stacker.GamePieceType; import org.usfirst.frc.team3316.robot.stacker.StackerPosition; @@ -8,18 +9,12 @@ public class MoveStackerToTote extends MoveStacker { - public MoveStackerToTote() - { - super(); - } - protected void initialize() { /* * If one of the ratchets is not in place and they should be pressed, dont start */ - if ( Robot.stacker.getSolenoidContainer() == DoubleSolenoid.Value.kReverse && - Robot.stacker.getPosition() == StackerPosition.Floor && + if ( Robot.stacker.getPosition() == StackerPosition.Floor && (!Robot.stacker.getSwitchLeft() || !Robot.stacker.getSwitchRight())) { this.cancel(); @@ -32,12 +27,17 @@ protected void initialize() protected void setSolenoids() { - if ( Robot.stacker.getStackBase() != null && - Robot.stacker.getStackBase().getType() == GamePieceType.Container) + //TODO: check if the condition should be if the command started when the stacker was stuck on a container + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) { Robot.stacker.openSolenoidContainer(); } Robot.stacker.closeSolenoidUpper(); Robot.stacker.closeSolenoidBottom(); } + + protected boolean isFinished () + { + return (Robot.stacker.getPosition() == StackerPosition.Tote); + } } diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java index ec1b36d..fcdbe36 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java @@ -32,6 +32,11 @@ public class Stacker extends Subsystem private AnalogInput heightIR; //infrared private DigitalInput switchRight, switchLeft; //the switches that signify if there's a tote or a container in the stacker + private double heightFloorMin, heightFloorMax, + heightStepMin, heightStepMax, + heightToteMin, heightToteMax, + heightStuckOnContainerMin, heightStuckOnContainerMax; + private Stack stack; public Stacker () @@ -125,25 +130,57 @@ public boolean getSwitchLeft () return switchLeft.get(); } + /* + * TODO: check if StuckOnContainer is necessary (if it's not simply step or floor) + */ public StackerPosition getPosition () { - /* - * TODO: this method should return a position based on the stacker IR - */ - if (solenoidUpper.get() == DoubleSolenoid.Value.kForward && - solenoidBottom.get() == DoubleSolenoid.Value.kForward) + updateHeights(); + + double height = getHeight(); + + if ((height > heightFloorMin) && (height < heightFloorMax)) { return StackerPosition.Floor; } - else if (solenoidUpper.get() == DoubleSolenoid.Value.kReverse && - solenoidBottom.get() == DoubleSolenoid.Value.kReverse) + else if ((height > heightToteMin) && (height < heightToteMax)) { return StackerPosition.Tote; } - else + else if ((height > heightStepMin) && (height < heightStepMax)) { return StackerPosition.Step; } + else if ((height > heightStuckOnContainerMin) && (height < heightStuckOnContainerMax)) + { + return StackerPosition.StuckOnContainer; + } + else + { + return null; + } + } + + private void updateHeights () + { + try + { + heightFloorMin = (double) config.get("stacker_HeightFloorMinimum"); + heightFloorMax = (double) config.get("stacker_HeightFloorMaximum"); + + heightToteMin = (double) config.get("stacker_HeightToteMinimum"); + heightToteMax = (double) config.get("stacker_HeightToteMaximum"); + + heightStepMin = (double) config.get("stacker_HeightStepMinimum"); + heightStepMax = (double) config.get("stacker_HeightStepMaximum"); + + heightStuckOnContainerMin = (double) config.get("stacker_HeightStuckOnContainerMinimum"); + heightStuckOnContainerMax = (double) config.get("stacker_HeightStuckOnContainerMaximum"); + } + catch (ConfigException e) + { + logger.severe(e); + } } public DoubleSolenoid.Value getSolenoidContainer () From cf99e6a16423f5a681bee5b3136c027c41f43348 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Sat, 14 Feb 2015 14:34:09 +0200 Subject: [PATCH 04/29] Fixed all of the TODO's in the code --- .../frc/team3316/robot/chassis/commands/FieldOrientedDrive.java | 2 -- .../frc/team3316/robot/chassis/commands/RobotOrientedDrive.java | 1 - .../usfirst/frc/team3316/robot/sequences/PickupSequence.java | 2 +- 3 files changed, 1 insertion(+), 4 deletions(-) diff --git a/src/org/usfirst/frc/team3316/robot/chassis/commands/FieldOrientedDrive.java b/src/org/usfirst/frc/team3316/robot/chassis/commands/FieldOrientedDrive.java index 7030b8f..4ef0e3a 100644 --- a/src/org/usfirst/frc/team3316/robot/chassis/commands/FieldOrientedDrive.java +++ b/src/org/usfirst/frc/team3316/robot/chassis/commands/FieldOrientedDrive.java @@ -19,8 +19,6 @@ protected void setFieldVector (double x, double y) //clockwise is positive and //counter-clockwise is negative double robotAngleRad = Math.toRadians(Robot.chassis.getHeading()); //Robot angle - // For D-Bugging purposes - SmartDashboard.putNumber("Current Heading", Robot.chassis.getHeading()); //TODO: MOVE THIS TO A BETTER PLACE double angleDiff = vectorAngle - robotAngleRad; //The angle of the vector oriented to the robot diff --git a/src/org/usfirst/frc/team3316/robot/chassis/commands/RobotOrientedDrive.java b/src/org/usfirst/frc/team3316/robot/chassis/commands/RobotOrientedDrive.java index e01b69c..a44e417 100644 --- a/src/org/usfirst/frc/team3316/robot/chassis/commands/RobotOrientedDrive.java +++ b/src/org/usfirst/frc/team3316/robot/chassis/commands/RobotOrientedDrive.java @@ -21,7 +21,6 @@ protected void setRobotVector (double x, double y) protected void setRotation (double requiredTurn) { - //TODO: figure out PID rotation //NOTE: Required turn cannot be larger than yIn. /* diff --git a/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java index f17f047..a7ac25c 100644 --- a/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java +++ b/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java @@ -21,7 +21,7 @@ public class PickupSequence extends CommandGroup public PickupSequence () { - addSequential(new MoveStackerToTote()); + addSequential(new MoveStackerToTote()); //TODO: check if this doesn't cause bugs addSequential(new RollIn()); addGamePieceSequence = new AddGamePieceSequence(); From c7880d0bcf490288f36471885fe476c61b67aa9b Mon Sep 17 00:00:00 2001 From: frc3316 Date: Sat, 14 Feb 2015 13:56:57 +0200 Subject: [PATCH 05/29] Finished adding PickupSequence and fixed MoveStacker commmands --- .../frc/team3316/robot/config/Config.java | 35 ++++++------ .../robot/rollerGripper/commands/RollOut.java | 7 +++ .../robot/sequences/AddGamePieceSequence.java | 2 +- .../robot/sequences/pickupSequence.java | 37 ------------- .../robot/stacker/StackerPosition.java | 2 +- .../stacker/commands/MoveStackerToFloor.java | 13 +++-- .../stacker/commands/MoveStackerToStep.java | 30 +++++++---- .../stacker/commands/MoveStackerToTote.java | 18 +++---- .../team3316/robot/subsystems/Stacker.java | 53 ++++++++++++++++--- 9 files changed, 108 insertions(+), 89 deletions(-) delete mode 100644 src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java diff --git a/src/org/usfirst/frc/team3316/robot/config/Config.java b/src/org/usfirst/frc/team3316/robot/config/Config.java index 307d44b..4d4b9f1 100644 --- a/src/org/usfirst/frc/team3316/robot/config/Config.java +++ b/src/org/usfirst/frc/team3316/robot/config/Config.java @@ -152,9 +152,9 @@ private void initConfig () addToConstants("CHASSIS_ENCODER_CENTER_A", 0); addToConstants("CHASSIS_ENCODER_CENTER_B", 1); - addToConstants("CHASSIS_ENCODER_LEFT_DISTANCE_PER_PULSE", -0.07363107781851077902646820429561); - addToConstants("CHASSIS_ENCODER_RIGHT_DISTANCE_PER_PULSE", 0.07363107781851077902646820429561); - addToConstants("CHASSIS_ENCODER_CENTER_DISTANCE_PER_PULSE", 0.02454369260617025967548940143187); + addToConstants("CHASSIS_ENCODER_LEFT_DISTANCE_PER_PULSE", -0.0018702293765902); + addToConstants("CHASSIS_ENCODER_RIGHT_DISTANCE_PER_PULSE", 0.0018702293765902); + addToConstants("CHASSIS_ENCODER_CENTER_DISTANCE_PER_PULSE", 0.0012468195843934); addToConstants("CHASSIS_WIDTH", 0.5322); //in meters /* @@ -270,7 +270,7 @@ private void initConfig () addToVariables("rollerGripper_RollJoystick_InvertX", true); addToVariables("rollerGripper_RollJoystick_InvertY", false); - addToVariables("rollerGripper_RollJoystick_LowPass", 0.05); + addToVariables("rollerGripper_RollJoystick_LowPass", 0.15); /* * Stacker @@ -293,21 +293,26 @@ private void initConfig () addToConstants("STACKER_IR", 0); + + addToConstants("SWITCH_RATCHET_LEFT", 7); addToConstants("SWITCH_RATCHET_RIGHT", 8); - addToConstants("SWITCH_RATCHET_LEFT", 9); /* * Variables */ - //MoveStacker - //MoveStackerToFloor - addToVariables("stacker_MoveStackerToFloor_HeightMax", 0.4); - addToVariables("stacker_MoveStackerToFloor_HeightMin", 0.42); - //MoveStackerToStep - addToVariables("stacker_MoveStackerToStep_HeightMax", 1.05); - addToVariables("stacker_MoveStackerToStep_HeightMin", 0.95); - //MoveStackerToTote - addToVariables("stacker_MoveStackerToTote_HeightMax", 1.62); - addToVariables("stacker_MoveStackerToTote_HeightMin", 1.45); + //Subsystem + + //TODO: re-determine these values + addToVariables("stacker_HeightFloorMinimum", 0.4); + addToVariables("stacker_HeightFloorMaximum", 0.42); + + addToVariables("stacker_HeightToteMinimum", 1.45); + addToVariables("stacker_HeightToteMaximum", 1.62); + + addToVariables("stacker_HeightStepMinimum", 0.95); + addToVariables("stacker_HeightStepMaximum", 1.05); + + addToVariables("stacker_HeightStuckOnContainerMinimum", 1.05); + addToVariables("stacker_HeightStuckOnContainerMaximum", 1.05); } } diff --git a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java index 2952d45..d63ec41 100644 --- a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java +++ b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java @@ -1,6 +1,8 @@ package org.usfirst.frc.team3316.robot.rollerGripper.commands; +import org.usfirst.frc.team3316.robot.Robot; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; public class RollOut extends Roll { @@ -16,4 +18,9 @@ protected void setSpeeds () logger.severe(e); } } + + protected boolean isFinished () + { + return Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.None; + } } diff --git a/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java index f7e1c78..2b6fb26 100644 --- a/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java +++ b/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java @@ -13,8 +13,8 @@ public class AddGamePieceSequence extends CommandGroup { public AddGamePieceSequence() { + addSequential(new AddGamePieceToStack()); addSequential(new MoveStackerToFloor()); - addSequential(new AddGamePieceToStack()); addSequential(new MoveStackerToTote()); } } diff --git a/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java deleted file mode 100644 index f17f047..0000000 --- a/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java +++ /dev/null @@ -1,37 +0,0 @@ -package org.usfirst.frc.team3316.robot.sequences; - -import org.usfirst.frc.team3316.robot.Robot; -import org.usfirst.frc.team3316.robot.config.Config; -import org.usfirst.frc.team3316.robot.logger.DBugLogger; -import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollIn; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToFloor; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToTote; - -import edu.wpi.first.wpilibj.command.CommandGroup; - -/** - * - */ -public class PickupSequence extends CommandGroup -{ - DBugLogger logger = Robot.logger; - Config config = Robot.config; - - AddGamePieceSequence addGamePieceSequence; - - public PickupSequence () - { - addSequential(new MoveStackerToTote()); - addSequential(new RollIn()); - - addGamePieceSequence = new AddGamePieceSequence(); - } - - protected void end () - { - if (!Robot.stacker.isFull() && Robot.rollerGripper.getSwitchGamePiece()) - { - addGamePieceSequence.start(); - } - } -} diff --git a/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java b/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java index e7867c1..4ae1df1 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java @@ -2,5 +2,5 @@ public enum StackerPosition { - Tote, Step, Floor; + Tote, Step, Floor, StuckOnContainer; } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java index 2eb2343..98bad13 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java @@ -3,13 +3,13 @@ import org.usfirst.frc.team3316.robot.Robot; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; +import org.usfirst.frc.team3316.robot.stacker.StackerPosition; /** * */ public class MoveStackerToFloor extends MoveStacker { - double gpDistanceMin, gpDistanceMax; protected void setSolenoids() { @@ -22,16 +22,15 @@ protected void setSolenoids() Robot.stacker.openSolenoidBottom(); } - private void updateDistanceRange () + protected boolean isFinished () { - try + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) { - gpDistanceMax = (double) config.get("stacker_MoveStackerToFloor_GPDistanceMax"); - gpDistanceMin = (double) config.get("stacker_MoveStackerToFloor_GPDistanceMin"); + return (Robot.stacker.getPosition() == StackerPosition.StuckOnContainer); } - catch (ConfigException e) + else { - logger.severe(e); + return (Robot.stacker.getPosition() == StackerPosition.Floor); } } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java index c806f29..adcaf7d 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java @@ -1,28 +1,19 @@ package org.usfirst.frc.team3316.robot.stacker.commands; import org.usfirst.frc.team3316.robot.Robot; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.stacker.StackerPosition; import edu.wpi.first.wpilibj.DoubleSolenoid; -/** - * - */ public class MoveStackerToStep extends MoveStacker { - public MoveStackerToStep() - { - super("STACKER_MOVE_STACKER_TO_STEP_HEIGHT_MAX", - "STACKER_MOVE_STACKER_TO_STEP_HEIGHT_MIN"); - } - protected void initialize() { /* * If one of the ratchets is not in place and they should be pressed, dont start */ - if ( Robot.stacker.getSolenoidContainer() == DoubleSolenoid.Value.kReverse && - Robot.stacker.getPosition() == StackerPosition.Floor && + if ( Robot.stacker.getPosition() == StackerPosition.Floor && (!Robot.stacker.getSwitchLeft() || !Robot.stacker.getSwitchRight())) { this.cancel(); @@ -35,7 +26,24 @@ protected void initialize() protected void setSolenoids() { + //TODO: check if the condition should be if the command started when the stacker was stuck on a container + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) + { + Robot.stacker.openSolenoidContainer(); + } Robot.stacker.closeSolenoidUpper(); Robot.stacker.openSolenoidBottom(); } + + protected boolean isFinished () + { + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) + { + return (Robot.stacker.getPosition() == StackerPosition.StuckOnContainer); + } + else + { + return (Robot.stacker.getPosition() == StackerPosition.Step); + } + } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java index 6a566e3..a8ef7e6 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java @@ -1,6 +1,7 @@ package org.usfirst.frc.team3316.robot.stacker.commands; import org.usfirst.frc.team3316.robot.Robot; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.stacker.GamePieceType; import org.usfirst.frc.team3316.robot.stacker.StackerPosition; @@ -8,18 +9,12 @@ public class MoveStackerToTote extends MoveStacker { - public MoveStackerToTote() - { - super(); - } - protected void initialize() { /* * If one of the ratchets is not in place and they should be pressed, dont start */ - if ( Robot.stacker.getSolenoidContainer() == DoubleSolenoid.Value.kReverse && - Robot.stacker.getPosition() == StackerPosition.Floor && + if ( Robot.stacker.getPosition() == StackerPosition.Floor && (!Robot.stacker.getSwitchLeft() || !Robot.stacker.getSwitchRight())) { this.cancel(); @@ -32,12 +27,17 @@ protected void initialize() protected void setSolenoids() { - if ( Robot.stacker.getStackBase() != null && - Robot.stacker.getStackBase().getType() == GamePieceType.Container) + //TODO: check if the condition should be if the command started when the stacker was stuck on a container + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) { Robot.stacker.openSolenoidContainer(); } Robot.stacker.closeSolenoidUpper(); Robot.stacker.closeSolenoidBottom(); } + + protected boolean isFinished () + { + return (Robot.stacker.getPosition() == StackerPosition.Tote); + } } diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java index ec1b36d..fcdbe36 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java @@ -32,6 +32,11 @@ public class Stacker extends Subsystem private AnalogInput heightIR; //infrared private DigitalInput switchRight, switchLeft; //the switches that signify if there's a tote or a container in the stacker + private double heightFloorMin, heightFloorMax, + heightStepMin, heightStepMax, + heightToteMin, heightToteMax, + heightStuckOnContainerMin, heightStuckOnContainerMax; + private Stack stack; public Stacker () @@ -125,25 +130,57 @@ public boolean getSwitchLeft () return switchLeft.get(); } + /* + * TODO: check if StuckOnContainer is necessary (if it's not simply step or floor) + */ public StackerPosition getPosition () { - /* - * TODO: this method should return a position based on the stacker IR - */ - if (solenoidUpper.get() == DoubleSolenoid.Value.kForward && - solenoidBottom.get() == DoubleSolenoid.Value.kForward) + updateHeights(); + + double height = getHeight(); + + if ((height > heightFloorMin) && (height < heightFloorMax)) { return StackerPosition.Floor; } - else if (solenoidUpper.get() == DoubleSolenoid.Value.kReverse && - solenoidBottom.get() == DoubleSolenoid.Value.kReverse) + else if ((height > heightToteMin) && (height < heightToteMax)) { return StackerPosition.Tote; } - else + else if ((height > heightStepMin) && (height < heightStepMax)) { return StackerPosition.Step; } + else if ((height > heightStuckOnContainerMin) && (height < heightStuckOnContainerMax)) + { + return StackerPosition.StuckOnContainer; + } + else + { + return null; + } + } + + private void updateHeights () + { + try + { + heightFloorMin = (double) config.get("stacker_HeightFloorMinimum"); + heightFloorMax = (double) config.get("stacker_HeightFloorMaximum"); + + heightToteMin = (double) config.get("stacker_HeightToteMinimum"); + heightToteMax = (double) config.get("stacker_HeightToteMaximum"); + + heightStepMin = (double) config.get("stacker_HeightStepMinimum"); + heightStepMax = (double) config.get("stacker_HeightStepMaximum"); + + heightStuckOnContainerMin = (double) config.get("stacker_HeightStuckOnContainerMinimum"); + heightStuckOnContainerMax = (double) config.get("stacker_HeightStuckOnContainerMaximum"); + } + catch (ConfigException e) + { + logger.severe(e); + } } public DoubleSolenoid.Value getSolenoidContainer () From 75f12e7ff6e28f33bf9cb8497a600bf8967065bf Mon Sep 17 00:00:00 2001 From: frc3316 Date: Fri, 13 Feb 2015 01:35:43 +0200 Subject: [PATCH 06/29] Added game piece switch in roller gripper --- dist/FRCUserProgram.jar | Bin 1805973 -> 1806194 bytes .../frc/team3316/robot/config/Config.java | 15 ++++++++------- .../frc/team3316/robot/humanIO/SDB.java | 6 ++++++ .../frc/team3316/robot/robotIO/Sensors.java | 7 ++++++- .../rollerGripper/GamePieceCollected.java | 6 ++++++ .../robot/subsystems/RollerGripper.java | 13 +++++++++++++ sysProps.xml | Bin 5950 -> 5950 bytes 7 files changed, 39 insertions(+), 8 deletions(-) create mode 100644 src/org/usfirst/frc/team3316/robot/rollerGripper/GamePieceCollected.java diff --git a/dist/FRCUserProgram.jar b/dist/FRCUserProgram.jar index 9c96f4406d5d3977cb45f2353c317e8af5653e9e..56967403520a0a7ebcc1860934e6eb3f5a58f33b 100644 GIT binary patch delta 30244 zcmZTv2RxVG_xE}1y_3h@Gb<|@iDXBFtSDrUD3tm{Mz)BXkyOYiS)oWt5lL2|6q1mL zrc(Le=kv&y-@n)E>AB~9&OP^>bI+ZhN9INU&-wn07AE8rbYx^SWMo%p&CW4Ol3#`| z^?q_lWiSy0NN)v#6zT0qki*_J$%JeIsUSsu4KMUlxZwp2st&wBMH7Y>B57|hk!mY$ zRw7mM*c`!3DojemGmtnz$~dQ3*%2XeDAn%amD|)CZAeykRFJd#FT4CY3Qx!I9CU!B!KiH_uLLF4PuxE8A9rM7P??klu^7 z%A~iXod))Y`fYT5;si5IHNh$z(ae@L!lR)V*9NlR!7Ra^0 z5NVWkEy6TdgllfO&*P31d*XF#QhdE|`+xcQliI8CIUELxePZ!_?`ZFxFBzO3ea`1K=lfU7f*Q6U`oa&57Tr@f}5SRFoRYO8DZe;H! z)%}spgmY+erw}I0=9ZT0nU5*S$ov=pt2sd|Lm`7EV@ED?&9?j@N>UY$!WX#Kx#HD! z6H3bQz^Y$w#5@dAw+-VN z;i|ROMw5YzELDJvObLcZBtzjnRmSvVCL(PJ&vVYZd#)OeCZwyUq+ht+jRfUA8a~Z& zO|h=+NCB>sIP@LiM4g_e?UC{}A%1J@7E@xG6f z#8Y#hPxCQrxU}+9>u44_@xR~~=#{%yKVeCo7iM}QY$Qd3cXNyuvd8KfW-k zXWmIu6n_O5c1P-LThMgw@x3d#kbeIOLfjO#YiwWSAjMzdg**3okN~>h`^L6J)>FP= zUCO;bO8JH}Y|oeg@`*k|aN+X(-G~7FZ!6*$d*mKU?Ha9yFV8c~oiyjdssF}2qin9+ z$Ad%?UzOFHEz7;jwv}EGaQOD>yM(R4H`B)Z068$s|C{00o-v=u0E*_LW7{L-7Y;-U zP@LkR&=q|wY{=@yscf2NmgbbkVlDbu$g@H4S^;a60UatnHRHI4Q{h9rg&ca(V%)uhR^IF zt@#1X3h~!fhSEjFG<9}YYOKuIHvMGp=W0Wui*SMe<8cq z@yF_PIt7x;8MC+W47eF?HIrPFcqv@9sntx+(<~sVI{7Dg%t*1sO{HADV=np%d|s~{ z1!nr@0#j};8=lziYV-5&!-8#PzBZ|YO&|0m7>KXXc=v()EJ=1<=w3InC8Q!^i zmv`tjX!pEjq}EfJfBvR8P?E)YoZ0g!`?42PY*RAvPkk&RlydZXuRYhoi3jsL^h(+W z$J}#^Vw*Z?(-mLTsLw*J4&Cze6kWlPey!KJvt&JZQm#L|viSC2dIMh>_h;PIibxy2Ih{8+nT zlNsOj_!m3HZ5TRMkk~9nrM%;B&iHot(z^9IWq)NE5NT(0y8CTq_U^6FPq*}p56TO~ zdKO-jV0X*@Xys31btIX8)c8P&LHSJb)62dw-#(rx$n;27Ad0ZjZNy7 zf%XfDzIeAvlYQYQG_~64LP{4O6dD<@Dt|}EGgZDdyXsn3sEkDtvUyovw1r)Q4C zZNc;XE6G>XtqMwwMEPAZlA4Boxv9y;0};WT%a2qT0OPb>zC-ZO6 zDBmdc`uuf|=jXbx+}h-)1KQCq$v#EQ28;i4H{|JGR(O}MbJ*j6DAB9*I&()vaN)(j zQhf=ng`V;?Pr^?8JoDITiZMH2VNx@0TIt zDgpOAd)4=3N7cI6&vmM)DwGo)F6-O#4cTa$)To3i9B7Mv`$phT-f4pDw0rcu>EXQ^ zY{}Pbd?Z*8J)zIDx;}ffkLc1#e^I&N33X_~-Z8SPF)nJ_FKJEaLz*sC3<>|XX}f*C zi)ZXYVS7A5CLu&v=56-=H{fv+u zyUKR{$&WS{>u;M+?h(E!V3M@u$GhN~w`KfV1L9$!o8oZ~G(FN}L?4Q~&o_coa9ewbb9*=}x7LOhXV zF=%orG%Bc%MjY_=zb+m) zf7(8!<&5IOTNm^1N3K7xT$pkXxtnz8ZrAj2k*fy!)Xxr%I7u>T5J?0n|1nevSx*9S9?c8TW+nJU)|c|0Hw_r9q7J|#igxJmB1LeRzYzYKCbIe*mI?>7pI2%54r9Ho{N`1Hl8kTg{9)!w;}V~K=Ps>k&96d)3P63 zM*XkK1XBC8JB4hYFV>na-d&ZO->UVM?t9PnhE(k~;-9Z#{9`Y_r9Fy_+ajlVFgt4Z z7S6D)YKlE}Ozjz2`-XhHTKcoDE;hNdJJ-4`q)#e0`ETP2u#;V4VI*+*03XvF5$9OE%o`pU&_7U0~Xt+8I$TX<}sQ?RDX;L~h^C zox?k>W^S=QaD{ib+#~~9o@X+VX;NZ+J4akntyh0iF6X-D4y(*-C8pu$Jfs3FZ+}+Y zCwZWsw>t37Ko2Z;Pjz2QWiA@SURbQB4E zK8YVv>;}u}NC?$i1{~p>n8MFEE0eC*WtL+h6GL<4@bK9@5baKXMAv z6KMYDfca*{id45=86h-MlMaW2Nh%Z-WMpKs@WD<$!T{D|0CIGMdnCSV)`K@c$jQib zXvxU5|M7*0exdBUI8KRgc|BLXgC>EdgdkI#+vjKhuIR?DoE>N~OGd3X=h2#M@mK!G zCYn$G-b9SiYR_t=CZ5*moVaMTljXR%)60w#^CRGJ{`Mc;A4gZ3mgw&@YW4=QmiLQl z4+hfuNY9&3(2w+2rd(Obv>xHgqDDK1EG$_QNZbN#~oB&Uu)gqMRn>) zYM1{=O;e{xjivp8%T4>*gRiJiZ3Uu1#}Zwur|Y-1W|vJY#s%Gcbf)uZEQ}WpKZg(R}{%4AarTt(B^OjCV`e>MI3L+iufvaiFT5uD>y+ z*gB!#o>TZM%6I37dP*TWhA$oI+_kX+)T+d>v)@bHE^<95PA{xGPzON)s}f?vxEMfx-2U)8&2LPYrd0x7p^XjF1{CpS&n*Ud$rn;drB z&6N`6#CJki^yIVIhZUS|^$oMH%)gq($$UJX`AL8H4(G6wd8Jm^!S-Ef(VZdBkBhpm zbsUP@Jbaky!|RBP141B0Ta)tM2O5`Y8rKhJD@z1D8vfMv8*p~KXg@cRV|Go#Dz@vJY%jA_DVNj51=UODlM=!X!YAU3nzal2bno^0R6wexcG z@Ci*rgR6>$#_+$FUiN(~$;GkM&9k2ic-8+jFT6Iof90>YG%@J*x2)0-fwPvkZAwAx zA=8^Q`(suNxADyk6s7N@atg zrpBYi=dwrIH9oCK-SRh?u4nkmIHNg@_mh!N`%**(1_ZTr5um50I9p2cDSCs6UOmj z`R3IM)(@`_Spxmw{sNCt-YZ!KB?f<4K296liw{d|^Ee%r`+-#xxWA`6O8z+Q80)Kn zRE~=Re~O+H32+kIOu82&-C7y^2wm!C!tMxJ$;cG`%@FiNxkJ9L!NC`86A$n{=lm;o zlRH)@ma()n*@OM+enB^}3(Bneh$xjY@-+RhPlju#ow)4Q5Ra_QugY%Km7cVlYc0EB ze?zP;`9`tp<-T9jjo<&Ay0;uUbSl(?R(3ym!@be&yFW%g<)3i=F%o>>9KPc(oCO~g&8FLb>}=_xwwyW%38Dhtq)yu#n?8=XY|vr>-_FqQ+?a^)8olB)^2$rFGDEnzH9hv#fo6OG#WtNRd#O%8m>#6{iK%;&>9xB1&AwFDj;sBBz*>sVE_gIdW! z(Z3-}@q*%A|6J?H=XWKNgGBPb-7t-~InKCzB>jG8bY>l+&TI~%#?@LI`!LD%+63+B zt&bs3G>u&zz4%p^rCNHT+}+_+?hdc(^JzQwU&|04lsUfT)yO42BA@bWLWhN5->hhI z*X5?@@PpYpzP&uT;Ic}6M8Dk&<}K<^{B1^uijEBOu}cc5DGl$4y*<<1lHt)8a84g)x zaJ3-3_4%e?>Q}LG zztJMQKlIlerWkMcwvpAp3p=+{TFE8q?ycyIqZ#k{P09+>Yj?@@^~Rl|+{V{fwY&Ys zkW6KnVcLf>467rP(v-Mt9_RD0X57!*GmEQIGq=a$DRgJ&VI$K}qU%XtR z=|&irM`jtebE+tDPo3xDJ2Fx-d7{@+!kuxykzPJ6AMw#Bh3ZjW-m}NP&6(@}_`#?j z`tAF7J~_GrQB!iE$kE??D?N*Q+$fI8DN>|&OFCtKeoG#!)i-HBku;hzSwYki>^NEB z-uJgull{+y8I9fuJKB-Yv3k{`Dq8&@@{2t8n-!1F$7fQfSjo+IB243z_it5XbX=If zQK6#hai^U*a9|?udxXrkBTd0WW6!g? zhZysdPF#(hy>{U*6<@2_BlaUhD%;(hCvOe8FU9VVec_PTdg{=CshH_@P7dUAbF=I1 zNhW#IC;Ug8r>e!;UmbjM`zf&cq)hqy$w?pU1k0_TgweFZto@(5&V`kS8F@@xCpNiM zBy4eH9Wc|2vwyLBz50rF%X6pRX;}zyXelNzyG2hVU;kXM8|2(BO1!!EO4yS}a<}dmoxkEyrciR>sfEAe!%E6Q z^Cw8eIlfJA_l?pTnI=}5MDFEy=C%-%$jpgK6i_~#B1oc z(u?#>oIL4f#iZ!JDRE%2b@A>(oH4)@5* z-xszp67$A#U)`q@t)ddI&_#1yU1bcW7c4b~gDXWVjvib`s~(x>P^_XHWU zy;n-Y7;`xpqzn^ZW^PyelbXgx*-E#IgUNGhPBY=|og-#Ydne{kBtoK#)*MIsswlot@aZsop}I zAWca+xAYpGve1G*cug~sktvgQC8xy+G~o9Rl#y6uI~&Trk7ea`UFEBga8Ak8&yp6N zl0yrdC}Wgq=N_mg8`(=r2j%+r7rlDjkjr5aA+uy)X&E6Rt!=^I_g(VCVpz(7-*0W7 zEoNN$!~DCT`?dZ~W4(`6TDNOL->U^rbzj_Gv;5`2XauthyWELNPU^CA_fI}=$YiE1 z`EA76BSRFP(G^f8{NcA25j$9bYA_vF;5@_Yc6KwH>*w7j`t}e1{O;W}PV+d-B2G4r zDN$YYZRKf^%=@3*rU{zUx>_km7W5GQ?*)X^g^sHTKl@?>wafy=B^{|TDb{vP&(5c* ziD5bYhxIj|%mfSPPkp6il|OQP=R=dcX4$bq>YHQxh=iN8>W>suyt4lsPq@6R>f?F& z*{`#88H?Xu867aNic|G>y!Ys^!(E#;K>iDn8#c&^%{2B>ZH+yWv#mgWD921{Uc_rq zoZ7m*_hMRh?Js4A-d|f8OgL}I&u%~e;^a1muWr+KsZWNpls=WSN&HYs=*zY0V)XQg z-EQMv)*8o6L^BIj-tk!1l=+w3O-XHVa8#R2kt2>)dW+xER&tu~tgArdYuz(CCdC}% zZx_(G8oI}3SZ18bd0i2t^G>ogfzA7rRgvUl4~-|^yf5k<7vILR&#Oo2r*-P zt*hwDhi>V``qz95$uW%nbkLtw z{=MALrpqFu6}iXXo5vb|`rw}saQcdwrA3Gp{o%OdD%&f*qYq2>T`%+wDd&*RnaWPm z3m#_I$Q$V6eyzkUI;=eNkU>M|scS><-u*-B-Mlf^q_-AiTs%7YvEk~7(Ug}))?C{A z+RZv$Oe%A~X5SD~GZ^wOWZuenDR(hIxAUq4Q(0?Sw1Ng@liaxKh@2}=-B#IVufIwI zlrR5OUEno|eh}I1BAH{cv+*tMz0+!K%J6pI!&3XgATax$*jcfXPC zO*{8|7d6{F8DDqPVo%A)3-j{x=WC6JS~#atxu|!JtFsclSc#?c@5;>B?{J+z6hu^K zG1foJKC}0rP;7P#AJq-nUG@+5M@Wu~M0AZ^9BPUGcwKJ1SAQt>Na+6i+h{Mn-OAtg zOpJo1kj|pnJ8&tS_EfEstjvkUaHU6oBDLND-pR59hBU5RH?04@wMtH$%bbY(u0OEn zkYs*hQnYHV)jnQ{31SNn4DMwks&DeNy>n18!8DimhYamD-kAgm#Q3l*$N9?T;*xGd z$u7$i>fV;MR+f*K>q>aXd;PwIT3nc9q09|196#Z;Ij-Y`&1vK5vAVjIODE*UOlY|R z&)s?Pt|Hv>*U|6%1L;i*Syil)BCRhw!c4`Kiq7>(-`s1bkX3b*xb>FbEu}ZqW!hK# zJ?`uiDZl+_-=@HLRka{zitDnU0&bLDRk@QHlhl@47=BVZ--gNmWxL7vyRNjY4o%ff z#A@#*k%6zbZSPdF-q~Hlw}pM6)T%Ez-t(BKkGg32XR6x|I*+K;D88+mDAVNrIJEm@ zNvUtJe^=#UpcqPKi0<=erM~RQsdj|(*E;##;GQyQ4QAJ{jbCCNbJef ztPs&T-1Mn;GeO#X#|}!xdp`W+KFvu9tk!I$Xv_KcXk?pQ zs4MFa=?^Eoxt!YGD#~)V?9EYIm;@=V!!%j_A-lSB+kBp+x=zyAoGX-)Sag=yuNCz^ z%FV3G%}@7;NmXHy;3B8V3r?b@-GPrSu~FS^2QQjU2}+4x*f|?;TR(396S?Y}mE4&P ziA+B?i)~(^Dtq8K(9>?brD(|BxRUSds2;7m1s&g23Jo)(;4HTHn!WVr6%JTc|2F(8 zVVre9((IJjFCMW@0k>~^LTa`RwcGc!z6?73O}HiHN-AGmo4L@VZkN+e(MC4T4AnB5 z4~{&xeF&rebo-LswZ};7-FjskX9nVE`!U_DJ8-je&Ob?Lb#8Y z6x9hYNUK&ooi^bij`i*!4C1A7J;FOuDdVxD0+8E<(t$36)irR~fKX53;rDwM``~)^ z#AuZ{WJJKfbg1_>A!OsqsLToJcm?>yi3!P~84Cgz&Lp=Ypm<4eAAy;I^jQYm3DJ*^ z@UkzCI-|-{48Rt6>rd?`1mo-NS4V<9Ub1u{JjF{wZvXUc_aN}$jX8J{c99yp>Pb+; z#a{am!tuuT`xDqm7n$|`A%r?QQnPC1`H`jYYmi`u4A!?|AU}ja4-OIuoWxmMc3YMe zC$=HC{S?9_w_Z@~it*fk-loig9VrJA)ymj<$Xp!y$tnPA-nfA zk6%kXzdygf|Jk3b$2CGjJ6g-mip6CQ-wyRSwKa79zWHm6&9v#dZ3h z%$6$2LPwf#ZjCHa*(XDEBGH_*l-%M8O3r7*T4UJ_Xs7fV1Sf>$jKZ8A@GxxQuBj}U z+Dye(oM~n9{fhr^${kO4>o^}7J-ub-vaD=XzUQw>%|MKeHc|2#480W3vIgjPIep7ZbDN$KQz<&k+i%=`F7ho;*X->ks~R0e zHI-+TU--XIP$oz1;Y<*VbF5uf?V!Jt(Q)a*q3OGEPL9uJQarAsv5Y&jyF955y97}U zvk6A*^2w6-7HiE`V?5&;a^s*~Z8Fj2gkedEjEudIPx%9Tj-%G{)7_i(3U2B=V#!mk z;kcr8nQN(|&p5|{-rk-fS=2NkzfaalbGfr1W6&>F&que?#A`WyZh=$Ymy_{P>e+=L z`O8MkJg!yS_BGv>=l`T*@~AQ~@9^E=45wiowj%2;Z>G>EI~6XF%^!VImB{TJLJX2HSS_$8Vhn*DI+&Gr%2vAV*m?pcRxuQ-r<9}nspVfAAj^xG}t*5J_9;K@Bd zkdhyA-qfMDkG^|nzPz27#2#9)r|FsF?MLe$Gd}0G>+ANRV>)Q}AeZjgq0}htuQFlu z0VWOC$M`<(V_|=nAh=8s&h^PC>_7`OakIrjw4lI2i^v4s*!Z|l=e;tz_dJu8QTEH< zyTGb#qY&vzxg50PfdpOKLTQu`uglQL*n7u=w=%>cipPQ@T6%=otQc>kSxtDvmz9i} zm~Qp;s?EDO`?Gf?*qg0+Zy@IZlO=R~SP;>(P4GWpU4PX)fA?Wx zL(A5m`TVpxQcK)}n_~s4?{R-0`EzIa*1nALSY_@PXBFioov5}$2-`pxjn*uhIu8*S^iWKl@X+G`O!iyyX}lleXkS;bGlM>KBJwdWKIw z&VBis@y^TV9}B~Srx+5xy*^}pGymefVEv@0#JL~D+@8XZiHRqdU-Y*rD;+t=G(T@L zAZOZl`R6&FnVVKmi$Rz{lZt)Kyq~d`LHx~=JuBfxeNXPcpSr!P&f$aJi{eX$mk&SX z5@1w$a8ZeI_mgus`F!pzq6Rzr?y(T8WJ6Bu2(h}zekP;unylnta;T+M;_d$D1=%Af z>#r2`5cLG)8>e%nOjndGg#LOKv-z=Q3`{OZnD_TjDsOi(zuG;ir+v-H&=Fx5$(io| z8WQt0Y02=Ts@+HNoK6}R`mA2l>yw)bm3HQH$mxlfe%o|j>7}NZ9`~G@<5b+)`5kAc z%_(|gY(hkKj@7e95F*lc2#7z9^NM>LQ#dLa6nmIh7MLP3R&n&v-yQAQucl>1*b-mw zER0INrOxBYB{^(kd{iX7;^)V*U%aiXqf=}-Gt~N0kK{gczSJu`aXZTF;p8dd+(&u~ zgJml;?tQ2T;BWXfO}8>fjfVK>BQIS@^Doq^4<`%S>2z8POf@ zimB_Ei(~OhX{^)Je#|}}uQtP$&)EBbqxfWq@b)T8|7!()oSOcBZJyqHOOUX+7Gb@HOyNChfBRGU=T z&4=2P3Wa>A3#mZOk2;YGhxt)wQsFT_x}Q`K6+rip3I_zC)^h@=1c_=CKuJq2pcO=| z{_%H`3Wb8`0aAfV2z4hF{Dsg%q{4s@dYDwu7DgROg^R+d8>v7cvRcbSWYvUr5!9N* zg8s;p3KpWM8mW*Vif$(r9*d&-qyn=TO8QO{IEtbBNJzFmwD+0Vs`K>Xs~-A@qd_G8 zs5lx(D*Vxbf_@UKs?Co>>VX8hgT$khL_J6ae@Qf$RCp(ehLH*fq*jsVQs{9KvR4|7 zCl%gEqi0A3H<{JK2bopYG1*n*_rF5amQ{s+wxGVGTE23qH>ofzx7tyv@~g;I`BkGg zDWHBN89z&C?_~v4lSGXvpkAbcsUmumRCuVk8ge-$^dJezP+AT7FC{d9g!pbTou%lBtxaT8k+!Bl(Z29t*WRWBlh9z+Q+6qOAWOW#31;? z>)Jn=wGs>2oUX$23`KWg_&F*)c&&z#zJ~@M)leQJoWuYH>L@GFR7ZtLt-7j1j_V*+ z1>=a2l(W=pY_Ek%X$WLwT5HP5$O&3t;m%XK%gT?frag>rmSG% zQ>&;iLZHnQAg};u%~iIaCS+?NK+ymd!hZRt0Z@h+lpI;*_hS5I+BH7umvL(F)0l^W z6qgM@k8g15C*4{l0g$4F;_@4QEZZP&%Dg5|58i8`Y$T_awP5=tTx%>EP{&2!1J2s3 z_Q4F}LALVZeC*1M*}{Z?aFAo4?UUwU(4q|`LRTeLv{5mV-QT8t{L0`r;hu1I*56>q zNj_W|6lKeBoL~nDI;(AEV*!pATx*L9>u@^Qqu7~;6nzzOoQYkv$^MTa21Y9r%EJ_7 zWDn^7xBri?R!iHlnkpME?>1O>P3FHAu**Ddk~ix_$hNEz*bq`x!sVHj2rSb70zq)d>}gVA@@UUP>DkXnk? zTOAj97++F%9iLg3AP5rlQ95CKHC`z;aX$)ev4u@pZ)gV5-&lSEufsMaPZbqh-AZD`!y3iR$??XFnEJKQx;0)anz>u!(= z1-gc)1*uQ}J4*j=pT>hq!__{eGlG7YIDsldR0nt%p_@qF5izvH1xGKr5a>X>E6PC9 zT6n?Nw-Fk612(_0=`g@zyy}GrP5%kZi+fOLeU=wSrh8z%DuDUVvqQ0FpnSn_L2?u(F|Z|l$;|q}-G7y=xcY~8v3Q9(%wn5b+P+*E0khr7Zn47%+NzfQxbS#1~*AFNd(YKL`A`<70Llj%~5G`?d1O;VQ>#Z)R&V9 zWbST90qb6rFDscq0oN|L; zwTif;5@-R(UQ`m%Ps8;Dq#~5SdoPqpT16B>QA+RtLk7}7i!HhtDAYndj8@Q9=5znK zDh{YlqbSI?LQ!(c^#5=xq%0Gwrv!L139O(r6lDQ%)+masT)^SL3j`jpU=15k$;A=# zebBT1>p1aS1fc`w*I{I2Y+=>$eX#1^3Y;fzgYHC{s&HaU6@eWz*g!qkYH(z84PHwc zk*voMHIQP9DiYp-`?jbTvi&ZGse;NT0u|UEhcW<{eJBM8wSx_e-orIm+#@i7)8Vk) z2@GC&fWv_g2%B+p_U}hg0!NlTY5?x+M|U9skFhu&MGX4!cwVwc&5?rxIPth2F1pyF zkGG`f096LQSmSYmyY}cNP=&!fLpbd0h%#h3qAG~q=o+vaX&b|dZbx(n;xdO5YEI~G zME(;_TyuiP^e(J&76@|S-r0ZcW_~8HtY#p#?znxyr8+-Drz)Ib{2IUE2;l&#iR}7| z6BhIc7dUwURYN-9p5!1Z2bx(B7GOY!Z~|?27$F{dWWCxC^tjX;7wD58JxtHiNf_fa z7nC14&$PyKK`dEu!rv8|{FQx8Hx-z1MGcTvZVU-Ty!o-WBp{~1sq7UW!oAL;zXxH+ z#st<0m>xoPkzAp52!jy92i_cl?h!@T!3!b?FJQ3#7aK3R4Nj=bgK>B0YLOhW8FaeA z%Ab`nL>WlCquL0$Dn@97(<%rfo)3@Qp(W-!F!%^Ez6)nN??PbWW8PPKK<|?bahT~a z?AH&*7@-V^CI}61H-^plgu!5z9)@}tOxJik!23L`FX##D-?hMD1q*0;nkO_$*#-o8 zLo>T=p%O7481UmZ8~iY`T_@0N1Fg;Xfvtpk!B$-D)_9x1J#Pq4VQ|WR43-DK?GSb# zgGul6hA^`u28SV8&e&T82>L)LWLHt2YgW{ zM8$KBkO9>;&|nEas9erx4MxFDZ-ffZtXzzz;fM1^{b1nb{nrR4u+JYR<(`1Gs#KuK zAC8MdffynSx&shq&`JBRhm8WDGRF{{*B*>;fF|*OyjvLW*$Is2i6|0rnVvwD8u$mI z%1GDgHDm{JDhekAkDzS8A_#gY7`qO+7y~ECVU2&9hk~HybMb2eddNu98o> Dy?) zEu3G2(JkQBIcQX!I1d{>O~?epssZV1JRv+No6jRGaHog=D~y~1_k*F)3jo*Z0AR`; z4uL(|Gp{)!?q4G@litNQ{5px|%> zx`iMKTu(t}Whyf*sEG z3gn!GO>e$~J9YXN3q6>@5ZhJ6$9i^a$jVPpaYum za8A>e#*sJia4Vh>4~LYT{2HQ(_^RTBN&nA)Lzw-cd#r_6A8J`vrHNLgY8FW8*~D>&}M2x|oF$KEJdup{4$ zIkp;n?qpco&UuYT2O6FJc^-`M%-q-UD&1hKq^JyHyb&jCcsXPy}XsUOO&55VU zmQ1MP@CzKi|D2o!lz0A1g6G2S#S@*II%`h0RJpFutjFq zA*Vk;t6^WkbI<%bSOma%WB&6x#N;zM6F3W?;N*84?gns_tNy`>)ZZ}I9!Ep(cVB>} z50HbF3vecgxd465r^g6agp(6{i-6tP5Nz6v6a1Sg7yx4xtQaClu|5&?gw_P8K)E0V z6R_j|H$jNyz&3}Oq#4iKIg$e_Uu`QY}rG> z0=73mKkD~x@FUi0omBZn*wA&mbqG~HwDE}JI^>xH1tXpXk}exG{cu^6;svM2{{>?> zA9`}meT_#27ThS9LA(px)+k(pJ83~LoacQB)k9K!aiZfAoUyzDaYDQRrVUL9PJ|Ue z8?T1q#IpjJLkcHwLh3R+yF8A>iGV~3S|A-s!GRC8`peLYJ+W&%M)2!0%%MwX*CF;- zV8(1p!jYR-pf$2tYixEv8er;Ip&qV$91grl!40GkI9mV=4!W`ivxBj#FmMNpaYUgI z+T2-+6LE#G12y2`8SB7pbrfuXrXB9R>5HI>vAQ*w8!$eE-Q|tJZSW+FNf#8MrpSdy zYXlWwDn_-Cq>gonUokX%U(Y(E_8A2ysA&9`T0e@R#*ydi1jeqxl~diX&vHJ z3Iq22H;(N2O~DG9OQA8*WPnf(*Pqc9I6n5Y{&PaM3~G#^z<46y4LK#;r~1Q$BJBa< zFy0ngj3*18mBEQJjS(Z95Fb|T%>z!9!~S>&$NP1Z5A5KiUoaQDcAA^br7I;`^p z4seV(dmZLUo&-kNA+xd|vJ$p<=>|NG?79J$pG<`{L>u8y!HHwalpJ7W1a@DXI_3IV z!)6;U(4bDa318n5E1i%GDw3UI{BFTVt>TVqk}}OKf5I;2bB7h#kTa$0|7O zBZqO~ZWT;1D?gkNsD_c#2*L?sH4M#c2w1E|1%OcqB|GT8`>%t3Rl}AF!f@W-P#BN@ zc>8N0&mscnRh*#Y#K-7u43<5;2E$K$Yv91|IfEl|XJ80ON&;))v=JJI!#8W;aFR{L z2pc3N1+xqVQ^_zc!vvTSq#fJta~tBaDIJ#zI7i8ZPedfC!CSEXt#IAOG%(h|3Fs+Y zvN6KD4u(J-F3%XziV;Vytg0x2Dx~XSzHBO9Lr{=b52IOEh9k^nlx$!cLv$-}M6Lk_ zj;_LM;R2Worw*tDa5Te6 z+$IBxeQ-nntQlp>6rf@Tfein0A*UIth4-uf`1(i&yd+x{W&zsw;577>aSdStx%c3* z-~sQ)Fqu#H;Ot7zxyGgj-W*gs*upK1B%|x#kK9y@z`yF>a2UD|Tm1olkHeJg;iF;) zf-SHLoMdoBh>8_-GQ;5=+XC-0KY`0F=sqM_5$E1Fp`rvI6sXv+^k)I~%2ey;6e*Q; zQh{1j^x)(J7-4q!`x4d|sWODQuqA*6EI)vT9MZ#i3azLS;%T}j$dAhyTW)B8d+(Y6 z1z2vyrUr*~h_gKv3tsQoL#R8(WgYM4Lu^8G!x0uYXas2wvh@)Z+~Tv^l+r?)h&Zy;24@ZO zXq<330}cCcZ8_c!t6HDMc{kf(I{78x1kGcZt%IpJA)gA(@_h_@u^Tx%#5*9&nv25<4OFzitphHG#7patv3%IsObbvt?#hO~u(`TX ziU!=fLd5|b(SPaf&_#S7%SpiF%Sjxcvn@q>kH(5%>J8_a_H4N@CWfD(*!q56c6KBomrd*K2Ql_?yRQKWsLWF4(Dy_g(vGBb8uKDZ{lId z>cuXI7uQ(35Xo;iar!F^Hk_TLk*hy(WO)fzBK52N?+qc5`hy8rk_*GXeF>tVM!}^% zRFzy2&bg2h2Y>tEPdECsB#Ikcq@m^jeq%5^p8fErn{sAqFfK~X4``WT#k>7bbdYlu zq8UK7$fe-+gCr2gP0bC615n^E9|;lwPJGnt;0*?y7g~j+pTl3tE{l;UWo*A7O}Kxk82F?>O$UDd`WLE}7cf);YB=wVDm5!+5)1Iqp=N=9 zlJoEKQ)LH9BR_B+gx_c_>#b7FgYeU>6Gp4lupxBljXj*`bcdj$JZ7tS#1QQ1#}?rJ z5d4J6#(EXi9)_C2>{hA#Vd%M{BMg}X^;WPSo6Uq?LM5LMkRa&!OZa_L-l0|TUk9nV zK-Wv?tNP(pi0c))lbqjYm5T7DW(Hj?|AuS!E9j+l0B{+ByS`(Q@aC7aE11FHLqRxv zKM*=kn!?0GsMp{8egg+aP%C8UI4;*W0#}jar*K02HL6U0A&S&0H#qhh+VCcJl~RkP z-n8zp^y@YBM=fcUsqhBXCBK-qN~I-IQ-EKo)SK~D;Px9RI-Rkexhn%^k(nqAF4rhz zJ_6LBcLmF2vrvz;z6++F{pm z;?@}KM%$Y((tlybRaQ`Q0{(Fr+se9CNU#f<$5;o=gJ(Z!^3KNfc;`5(N6y%~9wN3= z3jou%r~WHZ%cOp6NT?+c`5u0B zn7+JPbN(01JW}6sOu@cVTmcGG=w9RoIk-FnCwGeo8P3eHZSY1hFP)9_CZ z`cmK-la7UE{mx;SWuuff(!_xyrPHWBqPQ6&ct9c-4XNqX2*}L9_Lq5a-acL$e9pw9 z6NB*t1u&i~f=FU-X(0Cj=Fwdlj1U0=GBgaNNfxhA^Z`~Nmj^8$Pz@^KC-)7X#mbR21@LB1Wd&Ajd3)Mz{p1>QQY32@+c zmtb(3%Nk4#X6E7X_^i{Gn$7rl==u(8X?J7lxk1)b8Wf)!WPU)n zsvn14e!$b*{18qw{eTyI1|v9;|B8kUl$1a->E3L}wc$6ofaen2^X+?w6U|F-f3#y7 zC!A+sK3tljp~B}-wV4g|sXnYp!71@4bok|G9C`E;evaV#11IEuLG^CSIMMVA28T2o zRQ-b1n~(w5-!M&Qf5GeDixfEVi=37jWXD5;kJHeuAI(Ozn1Bo@U4~4DfOnk1`Ttgq3-~s39#2*h1iuMykv)1O;^Fv>f2$XBZ|x;6V}2 zy*TV|NeeHOF~RD6I3j>RJ$v`#L;%90fsi|`5p>`g#%^|5l_lrdhPc7s|F9PB9)fLp z?S~5kJSg)cGly}wlbmNeV(EhuW!|(*K%N3N_a+dqQu6SEZGkX`|J~T+P(b4>;73Uq zuRH|uNY_RkVH@ImAsiF1Lk3P^Z$Xeq$)k%eOm7TL6<%O`1M`6782AOY$p$Dx+Af`;g)(oOFc<|abUf7HJ}nGvQOg>l zh4{6D%Z!liMF-oAeu5MC=y=qS)Mq%sM$e;!fL@$%p@*EFL7b2pgrfp3eJsHC)rQcC z!*R~Y!w2XYptL(2(-=W{7T!R^D*9U72iuzo9v%KpP60`LB^$o2pt%dn_yiolB?Dkh5{XfCKMDx!cA zrXnh`xP+pp{Y+1dk@}ma(n&Lm+;X?3#RZ!v)Li;irqif6nVF^jzV|)w_`LJi`}uy) zx#ymH?tY(p!KQexgt1nRtL#9(g=!77#|4Sc#VE9%9N)!K#LE@=@3$y)lJw3n1?cGm zS2n`S*?!yNmJ5eEI-W275 zh8j6f0rs@^c?7w|0~!9Ois{TMcxXMiwf98Q$&2Z{KayHJkyO*bV1p<6%)%86+Lj}} z)~&y`(I&JP8d;&!3&(PCjVM`;7cx44TZzJ=mEPio=Cf$M!X!zh8x_!#vb`~u%D9~( z63pL>jI7^ZPk6(#KejOaz*|m}8n-gI_L^3vw;m(DiGQ_mM*BJ|9F|dzwQn-`;SH@f z_4k2O$!{}5e+Tn)HQwTbjCSp1nZsVKkp~A$tBq~V2dog{3)_1SGFa*>r${dyWpL|= zwwG8fg-fX?nQ1wJcs$+9ef*J)#Z4cx*6oi_Jx?n$^HW6Npr5Rjygy@wYkp`Ed8ZX% zPl>$|(G%yG+0Yx}Z@*NDlfTsJ`S8mTF_o@fv6VT9uSU_*zUzVxrmg;HyO!GmOp%7& zWAfQP7@2&2XHfqTE@4G#rntv8MR0f`6nsbF{xzyiZ$g-r^VDalqNx^cG^m{lb*c^=6>*YuWKL^8~ zkUq=m@dcK2v#h&)Lekjm0E z!*w#PyWG7zzxj+!A@+}CE%Qj7E3b+YLgDT3ET$_$;mhwi3NTW8C~9xPIA(57)HzaU z7@EN5JZ5Uckf1GJC63I8WosPl!eKdos!Em=jv4O}F5QV@bcUk@uZE*>?VGJI8PX-( zm+KNc(B!@l_gV

Pj_UDwfu3{)`XIjjY26oJ zD%9g-Iud76Jd0#(<0Ix|ZnF#N14W^geABXM(y0AnTZ=ftl+EvnG# z_;Rk*==MnDynZgrZddBDMT&&I2hTHOiGsby^BLsN*K4RH3S#>@!FbV>TD`k!tLYRC zW6AZ@5H0)BmO8yF<;Nh9GeFzjqWWk|<(V(B^sSA0{pJ{$nzMz8j2N`v7q&4tvs3R# zyJO^$Qaru_32RoyX8=0)&K(Mab@vXv12qpoC071jp@V6|d}J#Rgg004J*X?afi`F1 z$jMslY9U+po+yPUy**HVMta=JKp!ioN?Q*xI2tQ!Hy?s8OJd>b&xaK@QJQ;90b24K zgeIGDQpGGCgpu{!DHRiSN^jzp@Nf_^@AZjF79WT7b3RuwXFo$^cf}!ByE7{K_c(Ni z7tbn;hNi?LCO7{?+Y{tI^iDiFQymU01h^_0oGEe;A`z5;46_}X-tAy;qnB4<99aq4 z?mOC+AWxNwjY8^Affkrc$FV{Js<$o7pr>6S27bcDk=qewP!C$w;fkuOxCa_8P3fmF zdOFtEU?xi<=+O}ht)r$y5CpxWPGP+0 zw75`ePQjMt-wg_Fpz$d%@qQD1nrvP2F znKrDH-Klg0>MQFjrdvi}7{PZ-tInMfSjEfVGT8PE!iYHsM zS#WsW0A{Yo82eD)mED$HvN3S%rh5F)$ZS;YYlDPdmUJ^-{QA(pv$2%CZxH~SVT%#f zHyY;Fq_Me|Mq~f;V>adH%0cvGG>X14hr#$9NQRAJa6AWPj2y?nFISGXyFod*@_1>* zWaduiLgCW_2K@?*U9)9pA$onm81(wkX)J3QBd1H2VgUk4Hx^}eT0}#~!Tkwi(bq$3 z7`!DwO)Z1p#vwg9a3m7+Lnsud~rNlTHJ>Uts&0| zDA7kp=-Y|N$oGiRK$R1a^t_pjOw}P%sM4eq}GwNtv zqZqlwc)S0+O%WTv5Glq;TfP#%-gImdM(0QEMrW~5441y|P|^GIki~#YD#mpZ${lz` z#mt_BW@EXgFlkc8|0%$U`b|cO%5E`JJsH)q_YMQy9ixU;ebc@CeEFV@n=^kAT6i;a z4^97HW!;4tGzB4R{Z)}Uim}+8RtdWOv5G!51&-e7LAizKrqA>+^`ci2y0ePQhxT22 zmX+s=IYPtWU_J_yYha)+!1iIjk-_H%6Rz49AVNn>%$zEaW9EeCphYwbRp70!K`5@Da51=}r-Bra0gzSGm z6fz%rGFJ{G?@G+V2al?l`6sY4SmJajg!MoSmRkGH3$n?zD+@y;F&Gr=f zH43z=3gs;AuxUQ=7gSo$&6hK!ri-?WhHhU#)0(spi4!i{BzC%@QjJ`Iklg;!mT{sD zg7*CNzv(6S@gV2n0+b4OJsYa94Qp~TJ992Gs!*UDJkhAagxp~ezrJ+83iC-PMK8pL z^D`I0`B1Qn8QWIjn8wYl?i3wZ00{;EMR;wsM?W78retq-7g7hwX^1c_f?S{;N8D+A2|Vr7W} z1}k(|0S_!jss$lzvF*<&#M7z3c?o3i^reO+u%zn?OV$E5^|L8pUVou5MvBH$5~0`} z0k@tkL2h?(rB!%6D#~o^3TF*07GMEZg9Jk`O4ni>_@f5Hx)%m$0qSCr&8($J-5JNs zp`{oPK1pB@kpMAHySvI9TMK(F7_w_|bW?$mxmFIRuWK>8r48W(yOWW(^|Rc#6dSjL zhO$Ca3f#3S?5%^b$HRnkzVuTa`f%b129(N`+jR@Hq#lYgF4R_GhO)lM+E$N_bS~YN z(UYbD8=Q5cY-t_gP6*xy;t7mMf2;wENS}O_j{h>mV}7BEsa}SmrYG*yDjA*^Ok9bI z315!!@Zl~Mvt~JFiu3QOn27ffj3>(x+^`Rr#_O>ll8qQ$tTWug6)4#+`xTidO^Cr^ zf>m}w$ovl~G97uYM5#50x-vLu4xzje=m2l5gyP)83hhikt;D=`_n3;wJBE5JdI6r; zpJICQNwZ8x1=DawVS3T6(|8kAcCmYgjcbJMjptaQyb+7>?QIM!tB|!*o7qilLd@i_ z3W~{JDY7i-);A2SPu|kMFs)k%+Kb>6XhVMC58XapIba_Pb{Gp!I^z`%a;Q z#UzO=n~+iK_X^#Ue19>X%~L?YYpe8B3;r=mBK4G%-u7ySeizxfkN?5 ztgvA%s^QGP%s8W212-J+sOZYu=B|Ux`$&TC+soYbS#`6=a2)s?7^ly%tomjzPMIyute LrVsvD!=L^iMDi>Z delta 29186 zcmZU42Rv8b|G)RO_g?pHR>)r2BO?@{j1r+?W<)8gysapEA0w+WLfIpPQYocmlvGAa zDMX7;%kSLxl`sE)kH_tv=kxVCuk$+Ryw1FDUkZFP^L?53m{C$OP*BiOP&}^NoyxqG zvJbx02Pq*+XCVla-wFgt^7|k`4tv)p5^@OSgd}Ado*1NZ!4sM^5AXyHT@ap#pufgK z&aKF&M9$>KcZQXmcqegzi7fHohD%Df9Yn|yYPC*0bC3F4JaJuIR+H{wjRZX}+d z*L#E~M)U&-?9e~sW`BzGF-{7KJ4zH3lIfFFTS#_DI6IC|k`tPT-;opP)hi0=3h8v|_O1+= z0IcjGC;$;jlzpvz>9F>#Z*-lElZ-t={W|JkI2wj6~?M`e^2D z+CfM!3_4gJeVPN$pA&Q%A=fqdVpOmyLP6n1LqXw`ek)BXy(nA?sL7(t^%0?Zc>eQC z!T-sn`-UH^7Z2Nx=l2LN!V`>9Z1m*12qom=#kM7W$E#hRW{OGb(j#!y=uAIcV=1ei z%%oq-F(Kz&%3;AJbb0S_w{G34%DhiaLE*zhL7`1{OD~VLUZY@ynw){_$}`;NTWc;U^EhHD2kJDbhWRdwf=XS_e2VNxs0d;Glg z@lr=Io#YeHTs7>f^ziFE@D`G z*|vLw$P+qk>4l5To!y^RoJnj!P7~A-ywpw{%a^+fshoI%j3#U&wllViFSK?Mk>d=% zjV6k^91s%sa$eU;D;5zxP*IOW zB+Cvvh@asOcp|WQ;X=vJqVEq{ISV~Gmz%ptGQYM*{^eY@nNW^+;R zQX`G&QCW|KqRmu^+yPgL{3DY%Y@|Hei=P(v7}?YnwyAfZ2CxhlX*L$Z7iuXPuT=xgJki>b`m#(zk>kq5JyJn0=?6`)S#a zn0@E{obTNFetC&nw!wy^Yq@g3GnJH?B+7L1?$NnamM2%Q9dnoBNM@fMv)gUna%s}V z%A7;yX^=^5uE?YBcR2+!XIw(Jr0%wDlCYPyJ{C099(n9I_2huzLi54F<$${ya|do5&9N?GMCMGTeI zHaD`DW(ixc*cbKEoT}%sWz{^~U+TB*+G&!lo9v70hUV<0TpsTBqOImX)Zc4l9A&!a zc;k&LmGp_T?t^hTyV8Y`#ehq;j_6ZU74^;eC5?xBm|LEjj@KV$yk0wH@7*{R;w_f2 zwZHQ8?488Zui{_M2FTdH@K=)+mzlS`D-lR+f2DhN+`_CpSD`gj@Yq1AN1kd*JjXHj zZKPKfO_?ud)K4fi%5X@h8z5*FQMYruu<3gtRR7=$O|Z-N5_rj?-!0WET3NAufIV z%d+<4a0zFXO_gt!QG{ou!3W z_|0REB(B^+iKBAGRr_Pc(sR>0w$8d5RC56n%ae}}`;9!=8a3tV_up&d?8jqVD%ywI zq?HskLWgVmvgdQXDISm6daE=ZqVtt!y+;Ei?o4eN8kuDbs~_GIJXI~98zrzpJJDQo?mSJk08iv$>MQ9G)8ul6DoCU0%HMF(di=qK!8D2OHZl zA?{&HiX!#o*z^@7gazb+q4yYCL=JdWf3$#O}x>sn(eAG5$>T+ESk;(6%GF&QPJwqV)R}k4ow#y-zXL zn|7&;JKjC)Ur$PMUouE4Ydlp~w4(7x@qw!H)v~@X%hN7W1FfQO?RlqJhdxwvA6fjO zxyV*Et9e%aimvtp?zW+k6STi|Eu+Riv8a5S^1j;XSyKPtwN~+i`rCt7=Irk+i3}|V zJ2(`cd@61DGkYXTRPCFFTI{A>maaNG@8xa&^UWgF$(zO~)S4t1kvUdWsd~p*>$<&V zf6$b10H^!d^9Q@;(sLg=3Xfl*QBvn~MiYBD+gS%=7%e?wjpFYF-RHVOZFS7OqrT(7 z&0h@ntdEU%d^wO?&Hv}WSuw7_l}qoDZy+G1wX3txa^pMTG{JV{RP#|P zL#GdXw`|8cH>V+GoFr+wXS2K-li3Kfu-n!wh0aVxCkeM7{xk#c)WeyLqzc#<@5_AN z<#KQKZ^0S%N2zw9?G6!NmG*sW3=Fb(|L(yawT6$e+J8^~O_N@lHc5B2IW==OQ2Sb; zMuJS>`;*FVD&%B`?gW40PVx-f|NdnC7pdJ{nJog+xftalC6~!<8W5?3C1K-H$)VKMw zj;l1g`$gyek+JapDL2w|$d87(BbGCZqh9U>ZK&DZZ?F04oToJyqLwwm(RTktb0pa)$%@~{OLlk6CC+kNp(jgGS2ed zQ<0bB?_d(?Ln=gn3H}-skH67?m9)jQ)lmJ zkGq~4T$Rf0n10Pe^)j_J|G2|e*7`@?XU=Qi3+N-izU7*1e*g4NFqL|8=EWYV$49?Y zd>QdpQzh9a{ z|Jx(+gk+(le42tyc^B>5N5kKBdzMF(ahvgS->qw$(KxPrVjxH9_5r2arZ2j@XFQS` zvZYywnEvnZHbv0Uj z6g*b+?v;Ih(iu0(VKbkoh6S?&mv{7-4Q<)0cd2McAIG&6kCGjgTaKlAH161bKYoRZ zzwbiufQl8`n_jS`DI71?R#D1{X3^tVa)w{67VmdpuK+o&<&cW zmQQWt1Ax1R#eTNyfRVkU^L z+d6E;*(H@9T#?yS|K^Imso;T3H>rIVmnM5@(Bdl(iZ7a9&S3OxI6*B~e9+`*<}ROY z7B4JHdMUR#Y3NyJ@Oo5y5jVFUyUg(JWbWa89;Ly2eZ6yXkM6#BF?OeM_#h6!h+r{3d-8Sd##_!&lXmKtHf zPItaKi^dx8sN~56ibV)w=__BE>ci$O@PpEmuMGIv=he@C{8U!GVn8nJ+ln>WVzVhi zXd~+YItIcoX3V5t#r0!@loS*cfQ^x0LRvY^X~gwcT=sRqYXhdZqVs#rn0LK2XEG?J zF1gU~lukv`w(@+sOYZKr7m2?N-}0Y9Lz85Cwx6L8?w!hi5VPsq#ny`#Z{9dbI`j4Q z%|N%6zwe)PQXIVdMEvp8^tKDGoV+z@_pW)qx>qKy+b#Ic!TfTCj0$JrlrQRatk(BZ zl00c(+3K9iz_O{v=c^09JiW{BJ{QmRkgUCWhmvxfZ#nC*)a=7UO?MQ=7k(EAQfm#c z8ie+I9x0xPGA%jN_v2<0@8}3q>l^SPC z_8(TRVWmkExd-i=)D#m8Vov^dPj2PhOP0XU)6(BcUOHU&oR<^!D3!m#ZwCrS7ayF; ze6&U9`xIr?cLw((`}reneY5#Z*}QWO}0$VE$`searVHHW0tv9@f9c| z@8b1y&7{Sof$8$j;rmPHh||xgKU-a(X_7sYEX<_cu&`O^z%pHM%%I8Py63F2zo~qS ze2Sw?nB05D8WRuhrx6X*x^2LFyDRBj0mFk={-LSee_mzzwI?wZ+I^628)nlweEmVU zg)>{#o$I5i6$PFZiAma_BPtVid?Lqh-HoJX6{9qaA(iYGl-hJ%OW@o(m16=#;%-oVX-`01}#@4WjdT{~_|18aj9tAI?=>O^UH31qM4cBnYb@8_bHP>VV^F&4 zxeU#@LoHXf+e`i=xD_wcTAef8{oA6FYiuwz;q9+zf}K4{%~Pea-;e*K;_c(vLmeTa zS~rrdX|pw>_uemEQanpx{i%AcTeB>dW5nxwn$&kr9xB6&*w?wx0f`a|UjNB&BVX&b1Vx+OftC54Kb_*aau zM-E)?*WK-9G%D*=vX{4@xYT&@ZoH-cywT97=+=NuA2-eNH3kTLbdbMvo$cc_&b<$9 ztfeTA%@6Z6sv663vEE8LKKt-|VSjc4TlHR@xc6y~+ap+KwwsLxdrwmStS*n<{nPp1 zEJVIrGH#+0vSA0#tOOm>1!u13f-6Y^%1oCdxQThWEhq;so7&C>luq9+k&o)*rZ}It z?)jPo8ReHb2ZmJ52fx+04{SCc-6rmtdu%jUwf1mvao^LnnX}`8D@hIGYW4T!e5sJa z{H3waXU9MPxxN(Ixzt+;XMqW~-}~g3*_-8&asx=8w@dz@1C6TQoq;`Y_f@8Wm1s^xr7HTadGfa4PBz^(mUXKZg# zQ(H2kf|E|SVl4k0~uGb%Dl1~_&O=WRuax)FweRi8qiw@6Kj%VKs`pdp~JX0Qg`lnTE z{=zP#@{L>Xz|E?oJ6jsLN_9j^Pf2qph9-HIj52KP;C@Ne8r6)RpDT3@5#;FI#B9jX z+cvl5hSRW@y|MG@6GMJ9)Q0q=VkfQQve+*i(-+>2wd^|X?HKXw)feWRDqcIkg4gXG zsSn@zs*4vNF|~9*%g4NY%=`EE3Nn?olu3xQeB>9N?)ghHT46gA z)pJ3!ljc*)s|O3S`ANhDIVVRC=VWuG+_<&plvDo9<%b5$ zW+P{)ZIV@7)yJN`3(uMu@+uT4(&Rt^sXQ)eN6Jd@Qq{zsCWRGwQ!gX!s6mmb?MC#Z zPgYqOdphs9h3(wwp_2CE!-E8V=J45)zNegf1FZtvw+xP#U(*XW4&HAgeLPf8c>nM_NeP-S^IuIq3!o zqml6*ds0THZ`SL*x%NgpJF)&vWe7CCMjBgyDM)#Fz5YFSG9S5ZSz zZDBdD&CFs_i65yRmJ(hzwClWe5SsD)kds_Yp>|y>T;hU#RuebGjlK^NRGa z7-5Ew0$E2CrycJZ?uo2T*(&O}`@=QAhv#fx*$|oQ{vxTfwspPZG$p};obA2m-^lXb zctt{hwQ25EtFj|JhBt!gyLlY7eBu|xPTM8y*VYnIlr@&4W!QT#>cDv#JLmf$#ok|i z+|OGJs+~#x@7b%p2J_F=v0gz)+QjgmKa)?|94;IQkJe#F~>0~z}5O3u?x+~yip+gns( z)qbdClHU3C$&5ABw`(*^3LML8>WF66IH(o>>G9=ajfO=5gUBYu*aiMVyXOL<0W4lr z{?;sc?*4yTzr@zYduNtT3w%tblYQ?;`MpE2K`fR|Ej}7up7cJtGvUO%MqdfjTFOj|42)Y;f zRZm?kQT!Uiqa%1ZLnbxQphoFICXM7_n~u0^O7~o@TxrdH?eN#+z7+qI(%p2IixYl` z=NB&hru@yM;>(-7bGyx-9Avm4viz8<#r}aATXbcg^R!jX^asBP4JW>2*;${Z&}*}= zA31sS2%KiA&bgK6URx=0$gu5X%e$RN%Vj-Aqo$t~&Cun(+)>X~_fnGE!-0FLm}O~@ zk+q1PRmn!!Kubtp?eUis9pf3HvU7z+odq)e?}D6wZIDdt%Bl0Ts)N&xx9_Mh{CRbO z&%Nm>&E|v3yM*mCZC7YF>>HXJc?sw7qebdH1>h$@V8_lE&Cvn`O7hvIIZlv3PyXD} zoFziIN%Ky{z5KoJCQnnt+3cKG^-CAwx0P2XpXj(Rz3=S!CDdhcX2yVa zzOs9-KxMa}w|d;v?2LNym2lE8$2|&No8K7-(omP5;xiaMXV0XZB7SH`*VfP>>I8a) zk;{@I-BSeKtga(_9Q5|-CG`ZUENJm-Mx@Jao8+P_oL($q^zx4}7kaZ;6K-;FB;4f1 zZ$+VG#-Q8h`u_Vb9Vs~Sttz~X|EzIWeS)sUM6j{*g#Y7nyo(&kAh`W@F-g@GHMGw) z%=5PQJpNc{Kt}76V4c-iRYgK$^YPCM_S4}x-=`y-It@>!mim?sR@^;oBG#wfPyFzx z#Pxk@!|SVu?>4Dud0csCo#bqQL%y49%UTpL~V~xO8$9 zWtDDpBuM+ya)~irm8q#WJ!aErAobNS&VOW&ai9BEF6syO-)0xQ)Gc(t;r+K0O~^A8^ypm{iSYWQOvsbP1_ z&WyQBr<>h8UfdL@(2>2#WwPBU^R%>A4Ei{cxqP1ifB%K4tiFs(OHy1MxxCo|QPcHX zf|N?!>T*5(*u=Vv(x1*;w8`rp({Oe8%5;(|CU>^R_;izP-Bf~A^y9u7^M~Sn|M{Qx zcx`%b@%atf_v$Tg+#Z`=rQOy8XzH(g+es{k9lne&7oo*UGu+@l@Z5++ z8R}1kG=$#P)UJxYeMi_X#nPWw>9!*cR__=s8fC)lOqUHGWGCM{ zv`LtsU0fsQKY@^TSz@T;5H^QQq=xD^LEsTg*BCWRdz*{td_Rw1zmQ zgmTG!>e3_UYg42L4|_GZJTda8Wqe?+H&hF*WHXOu+G0Ex!7Ww zm-nZg^v5mfdzr=EeR=tD`o^4PN>%e27L_J}KWaJD)Rf=ujx|Y3dSshu`}3#%`wAX4 z1BsjW_tg^;H3eTsmmf1a*=k;gT82w{R|QPvUbfJ>CYkbdzGJIxYFuCAjsC;UL04AJ zpK4#UnIE+<{JJy2JMU8{<0)eY!TqwMD|Is$_ImFoJ@U?BP?TM;GpRlz_$@@E@b8dq zSJ;r9$6Gs}zz+q;YlkA6vjPI#vhEgQcZ+TK1x9U)ijho)Z-)pywYtVf)%KJ`m~bn~ zH(Nw_-HfTAx8b~+)7Ad$Q~BKSKQzO>VH~$v%k!ci<~$qE-sc>pe(pccmTPoQdl;O8 zlv|4FP6JXT?`tOCEw_A<{AxEJRJu@-ZfAUvCbsPiP4m;q>su$COsqRY->FpP-u_5m zRs5fQ)9+l#s=Tg{T;KblgJ+KZC+U5$OFYf{v6=SZ7FkXYS<|Kr(yAZCyh4 zbAAcLF8_HZt5?Au4PV#-*}GqfC9t6lN4Wc_2jbF?XYANn6uW%$oAddK&Rr2x{@KiD zk&*-37c2d!#1$_|d$7)ZyBi?y$ucQ>FhKWou3zxV7t+Q{G+?Mi*oiGXAW4a^mwYic z_s!8G4gR!2hdO;_MGPD=M2XF^%7jY@d6jX!l=kB&l>SL40C7yXxmiq=;Dg_(#a;UK z>Lk2V^I}Y|^$-L7hNxuoygK15dGTuY)g|1)@6J^83D5Bq>kh(Oaw`4)LAbP;5Ey_0 z{Exg8>X;CkaT&Jk>Ft8cp1kR*Oxu)z{{*4=u^Ax;w{^^dkVZ~nzXLHNn=s!?;KhaR z)&vxHGG=Ehe?7dVL+C(?3qcih?Lrxw`)vu`tBdUcLMNWGb0pYPlAEM@=9RS<%pydW zo;oasxgyX^I82DZ_0GBcE2PkkAc%X==|M0edqC?+P{Y;qy$Qj%FE@P&95iIZ#+%>S zyTIQ8C86oUSHwV}Im*|Jo+9`%kbh)iyl*%|0XC;IBkT?M8;VWfvj>3@uv(y;q>_EV ztU32{{gtaW&oUAVxAIcF$|EWjf25J8!8S6E*_7VA^6Urk8{RxwuLFd2e};9woFP4R z)*O5)>R*~a^X>iLz4-;9f%J!L@7#X->ZI`di=Qu^{0x5odGeWrsK*rAXvfcNk$aQ5 zMakgc4kwS`;=V2Z^x$s5K96b!9}90TQd)M8*AaW0h1NKq+a@%}%eP#o^S9kSZnMZU z#xtr#f6&@rFeWlBE-ZtyeCvc1&!LL)+ong@&FDv@vL?6saS!on_Fk_)l*6<+__^}; ze&-tP?fty%bwYkegS}_(`@cSE=38V!`+b*2LVC$uuJ{sPlCK-T;Lu5TLuGl}y7_G+ zoyvVvP6hH*Of%Zm(LeigOH3?w)?XXAh`u`SyG%@mI`mF}QY5Gs*N6h1}lX-hW_{(b$9bJ?7kfTMQ~2Kt@?D&?+m)ac#hnJ8g`yS>&emB6E`L+ZJ0Xm1&c{_N_}ssv$w0{ zBLG)XzTFhbxw@w+A9+Q*(+uz!^>0!0BzDNNje7rKL zyj$_x@rH{Ift3<}EuFc}T%Tk-b9F+R+4-pHEj6^`ZXnZ5BWZ=fdr72?#qi2i$15 z|1fe%OZrPA7qiyeJhgAz$M@}cuiJS`r*6(!m~^S0CoRTXXR2J_SKnV+zT{0$Q0t+0+0JPKhO*av`Iit|`Ui!g`Uqcf#37J0iC@ zPkr{gP#rB%HULEi1qb90tk%G(t)ptjX%k*YWS*7V@OyoWpD}9n4r1;~;`O`mX z2QqBp&WN$3d^m7yPYQQ=_m-b`uFO3zUEwOG<*rDKBMq6C)6!L*PtEcl^k*tgv{uX+ z65r`1_RG5OU|814L%X;1=Z?PUy58A8-erC2+YYm~=d$1bAhMQ~bF{>flO~#iSH2a9 zOCSTjAGyl+=wytDSPVW^7n6&;xutk6Bj2L`F~6r4Pn5QqFtuz}7t4;6f<;X?x-TKLexhaNr*@L_}x6MUHA z!vY^x_^`o;9X=fJ;e-zte7NDm10P=a@HHo&<97q(1$J2gRmXnj36urV?PTWH7L*85 z1W_(BDicIC$cZUIRF|CCB81wL6A?n_A#&oa5b8)y><~ts$cYkR^Z+?Q5J4@;32jkm z)mH?SAfs#%l)MyzX%W==pWJ|)h!91c$%!dZ)Rmkt+k_q^Cu%pL?&Jh^pc>Pb#WDxs&yiDISI zHfK~ukB}KZ<<&NSu8bZhGrP8}_EhaQG?2_ltE|?uSY zmz=9e4fP>!=hl9v2~hRb`0!Ili3mEJzIR?0w5p@z-wJ~V7y`f38f>ztqXkr`*$Vcze%#?Cz>cjx^6BVSkYK5f<+Tr zqnrAl)H06?Xetw#M6hqG`X%%NkFc#J{7tFWKWp%PCF0Awe^~^`Ud>~6cxTC^x)#bu z&i=ozy%ZFx8?p<}Lrry1u7%0>-RUBJ!JvNw$LI?W-+R zupP2`0vM|d=C`Aq!dQ2H|KR0Q0gn+Lu%$PeHU=Vks5QBKk%yW4>|mdNfji`lon|G1 z*;4{9G*LFFfSq5+4gOaQJT*W!gX8)r4G_^^bwOSqx?m{2CK4rEU%M}3{(n2#PkK$2 z2Fywmm_eL4kzo_L9OHHEKq0#Z*eK@o2Nbbv@~nHz2nZMD+OPY;9s`s}5CrT7DEx7{ zGJzgwNT5vQR`}mhi-JOL%@!8a{$%wmLsXdT>)NRc_J+X*#ltFCq1r%Dl|Tpho~=g1 z{|;gl6gxNQZ&AnfC)5cn;6KAv{n7-6A8xQa5ZIW88}$F^;QEJmpxoqM4&DJ9^Nt>1 zH$wHn^BpKkc5tQC%=HvBupb(**!ZY;mMCHjX z@xS9G1%>{Gmf*C-Rcm&^g#aEnX~2Eu)hhZ!3K2W7Cf`Oj^|!l0X&E-ECmbXu8%(`F zxTY!y3{6oUat#ieLMuBCtrNBU6FtR5TrRkX%?y<#XV5c)tehLp_PY_p|G(J%YXxK1 z0`!}$?oF6>L!5`e2e$K!n^6m|O_IqKrWdQRj*lR1kaKd`Ldv&Ip zgSnC2z8mG-z)N?vNe-Js`Qd;yIWySxU^QAdoQpS$qpm23L1t#{Qg5aYi%7RQMfS;D= zHkd3NOb9KAf($_m5ca~E zaZD6p1d|wXflOrWg$i0$5D(%CU7jc{$ixUi&}D@lAh=^MNl+AkPyrKb$X8>;R^V5O zP=i8@Si%T?z}yH;eS`#}lmZqkPz|hJ9AGLOMM0M2^_LTsX)no zSW<5txV0bkN6eaVoqju%8hF{EiU{qEHAWS2YF`6XK=%MF4(Y@h*)BLi)f|A{Y`Tpz zEcUQWwR>3WOMqZ|^e7<>?6pUYLH~U?mV7+n=+|(7MSBk5DrX!}3*_7&4oZe#YqA}L z=F*4P7;cd3fbxK(gD{uwbDVY>A@BmtW5m_UEMqdau{9YJFmZ%IFf+c6X?8@nAyKn9 z!{vmUAXf7@h;~AakZ+$?C5r?(AmR*Ni2Z^yWnT$=ARc4JzTwQ6Gpdbv{J{YX9bQoQ z7p^~gF0gWehoCF7^x&{7tUp<{nGxXzL^mi~W<=QFEfN0jN(3`tKa7ST&CF}cg5Vnq zA_9E0|5c1|1X>GVTT>7KhmN2MuecIY5%0LKv6099Vly&H~eG7doJ4NY4fT4R`iuQ!~6jviUZOnSpH5#s_P z{Nae!O@Wb2@<7CZyAP^_*tu_{rLk6I1601SpuNX7%D8~WaTv=%n9R`|mxcKtT%g|< zI$`Cr#;^dTgb(Zo2=47U?9eK9ev7Z=^T^JUxNx0@)L=>W1fVP=JAk z^B6deti)q)9Y8t>yF(@!)SiS>Nm?rQ)(4N$U_g+g{(Hs-*BCM|1zDhw2}_*ygDv$b z0Ja7vz@1djM%Z!M<`krVAI|5DbD{;as)K1fhCJ`gIKOVKX-!=&V6# zz(^2`+)_{*1YJ`IhBIDi&6)}`$O(oG!cf1CSqO&V`TKti5t}sGfKLc?da7Yfkrw=F zL`1QX$^fE6;i3>mf=iou6IhIZ1qp;g$5O~Z5d?>#(#RMYXn=7{qTGzBDT0+qI6@81 zKqjUc_?|(P87i9*ilfJU?%{^!b%19_!AkxyR$IYgBHLZh8iP;8+h(Lj%+j_FbqnxRvD3VL`HBA zV?zGNP=l0K*pS>LbSu)lN>9W>#UmuB_+yo+K2Kx?jgTQ|fW>cAKs&=vs~h00D097A5- zUR8^P&ChxVjt`id4b(-#h1nqzYSTx-tWCY(={e|$k_nL$utmeAH005S08f61DWISr z3JzeECu@Kfz(2QR0)I=PO^Ih4vS<(ET9(hC0$L6gp1LGMQEq5 z9NQkmz~!Uu8%FbkzVC39j=hB*-H3s?%9n9kgpQIPEXAN2a8IEai#i|;E9(R`v9MKH zXhHD>6wNvhM@I+4zcf7(C5P2TuN0eFqiQv#W5A!K<{3B?9DJRqwz5uKH zl>dLM*9EBNFN6`+$kZn6y&0@*rlbWTaZuGo5@Q5GXB^z2`NhGZxL0nCQAd(haKIA} ztq5pi00r_ol6tXG%_Y_XhF ztl$)!ew<3l3X*g2FroqySsSXWor!BnrJ*{=yKD>)!GAgbEO8fX(3Z-_6i}d3K*^RpNlu07Ek_9or$)uQ6;ucN28=M>=#hwQY^22iMwR*l1_K zPDQ&{jopE*m4q?!cX4JY1BS5s103jO!7VbWmy#`u2O8X;2@P)QTPMF?8jO#^Ldi2ja~8Dt?lnlwMg_pzW~)h*uUUF{3~o&xvO}9P=nLiC_lV@NXbTRkORLl6(QjF2dWUS z!KU4kgPB19As3$dkK{maZ!utCGkDEN#f8lbY~UTHqt1oVj>tGKE*{H;%gu#c*xqg; zYm6>pB!vV0JZLIR2?s@aa8@eXhJ)XEFr4#+msj3aeR@k2)b=EpQdN0_en5D;#uL zQ?Y}E=l{k{s~y$)5&2|4t~FHvy~}jKLDfMjW_+MiAKsvi9>Nup3So#exZq%+5PE0m zfdK)qs|fa5ofig(psWbaCke-KP~=AiKNA@yDp;`d&`2GS705_m0&;=6qZsk0HG4-&RjXBE&$w0U=fbja3F#$TO)7b=Ji7f z>>J9aHCi8;=>WA?VJAkF!hJy79UOcrg|1iM$AM`XYKR0q!9jHy+{dmA;ef3i`r!C- z4N!q&<#3OgJ++QG+6TRPT@H%{vp8KdN5u^efq&DC?o}v57I7Kz3v5^XAViJ_Os4W3 zler@kOSq0^1uT{SHwFZO{2wY7kXHd~UbaGR>C852UVLtgqoQ6P9EFsCy%Da8x|OgW z_t32Ycyr85O%JLnVPn@bZKT=2);8F5!R#9>C9&aJMeNj^AnX^WPzC*@<;H2YYcP@p zd8pw6j19b(m@EZdlc^xE!^oZ-x&~*6PVqGfHE6#EW1U3?V^HAd58WbOhdM3t>zFgw zVb7{B1TPRF02=EkE+Gkk;pmLy!kJ^Ww3?^wRCkr-`{ zg3Gh0E;0hn803BxV01ea@I zu?5}~$kt+Sc+*)2`~0{RY^=x|P^<{g2iTZlYlR`*b_06a*tW)~Bb8lifC{*`!YCBG zhcjKRa2kExy9O9R_7uts)Z3s@_x^Rc3WllaKyVxM`TWpEnh#90LB|zG*3pvfu;oTx z;!J-#jExI-;H;L{4$aO?tkGIX)%$h1q;5iI7H4oK{3dKm#`!fs3#M*Dqldn%W3)S9 zz>WRDnS~{4VJsq6H-T*(u&j<>tFjI_8@^h>fgU#vEqKC6L!0@Vh837I|J#QJcETKD z@D8OD&i1XH@RZZUfCK(6RFyyt_H?0#kqc}XCklqTptEvZfc+Ngiq!C9qzHI`(lCR+ zN&lwI##?ZiL_z;8xD$j~6uV(q$Zn#6#|S~#b4PE(@;GF0I_Ea*v>F8rh=N{4=-B_N zqNYN#euCV+4bwV=sOn&ENzmR6U5zoofDp(xq(Q-iC^WBq2bzyJTcepl^==v_kbDPr zmiAtZ76c=A;E)uv$AOju^bCsGfc0INwcHt}I}XwC;jL727am$(9>r<49{9EHrwa{3 z);(x&kNXmHDxbeLKj^$hLk}$TXas>%FU)_bU>$w4kcI=B zccqZvOB-oAaPcw?yoMtF3oZ4B(580jnie;pLWn#d8>6pPtoqt9gy#28NH| zO1-NSXObVm#XtHU4i+#ldLIX~4`_tI@jjRv?f}TH$Mw?)uiNeY9NG{>tV6gK-(%Dq zF?xoB@W*h>slLF$tH-Dfff6V_fwxdY6FArQ1TIHk-mGTrhjXRwI~?qprjZ1Xh5v03 ztNLNhhTpHr1i+tu7^O!(t}$@``H4mV_&$X$Q_QWSo1elRSoOj>1|5KInSH|<$L};; zr==z)RiI{J_rEqP-OKW)J4W6Uu> zJ-8u)M_egH$Pj1pM&MDeU?&cmcG04Mk3uWl&Nw4`h?ZsD4zl9thN^TP!L^meA1>0Hx+uogi1$6>_LF#Kb6V|+fi&cyt8DzbNlQmxeE|5P3TZVkpoetSh z=&xW*!3xPgiz|wc!ZnM0qaZj24Yx&L<)PqlBrPAfzV+YO4#i}Im^B$a5R8TW)>#c5 zdXCBL<8c}DI1J;iWE==((9(lfDYWFh&FajPH4c{xMo>Erj}ITRu+ZcOKLM>Mke`CK z>?feD&ODq>o`92`Zy`{83mtkt0S_bXmvQjq3T)SZcT7~keiG)&tHfm~lW^J#xsHRx zYS<-YMG+x*-^cU@&dGy~m`n(KY=TvUHCP=GK5w9rxmH|O_68m^6mH|-;C)(QFmZ^E z2J=x0G3r^P#j*JwUgJE(7+Jv92it^P4~M548r`oSQ}9Mkz&Qw0eDoI9%0^lbukGH96~0fu=i&0Tbhmu-wH>5g3gM|VYCpaHl!#%yOkqrMor1?_==GjiNaw4pqrLCLF-7jz>RH&fX<8d)JV1C3(sBkHX;yH4 z4m(%wTBG52+c#J<&%**5;B6h|nBF{`KU3hP90tm4>BMm7A7DC;cA)q(ye|tqu)%MM z&rn8v5SKxh)sT8;47ebot~j~f4Q7C4F@Y{Q7|o^&Fq(b6@iNZ&z=oFVhq9stxP#&K z!|AaFXea(81_anq&C(&XX{e;%wvU_5NF$geOL zWf4xde1);=eHjO=-{2g(sT>ESE6^F;t8{Q2e1rW_3a{rd%L?D&G2mtu9VbS!fuG-? zF}dnBnF(^V7K=xIz;Kg}6-3v;=K0@lQ~Jh+IMjn*Bvw^90R0bm_*`yVV~DHX{(uE! zb*|B@pt%dygnXqvg~_<@tdmJB!A59(fHUDsa6}yL!@<}RT>6IwaG$67bU1&fzdAV8-|lN9R@@J+X|d3Qt0VXQ1lzxaAjUcUtpmpVl+G0{0CO3 zoMWBr5hwj>+s6EXzDM({lj;6Nx$qk#qTmJ(6a+SE86mGl*BC~CY^LW}cO`vVd_(4V zu{Bj)gjx~<@_@7gXSutw7&wGnRl?p9pi7OO7W6CA)8L&SueQNXk?NWj`8dFq*+PW7 zAWe)F1!G$DEch;nlK|;0x;VXuKvYF^jc{<4K-`9u@5BHRwC|#aM=69Tg$$Wv3<~xj zL|sIEFAmJC=$SxIJ?xEp2(&kBgVVneXyTL|4t7%#H4*WHYk&b%Q9|*g^QtZ-Q3HuR zii2DiSlluzTojhvH&lzs9aj+cpl4s#i1(>rsR74u*8d$ldvug}3U?b7<0un|`M&YzpH0(O^wRT9#2Dg&o z*J7+RA}!GnanHm-FfCCZ;m^T=bS^#Ly6dMuw9px$d|akb0L^~tfj-*MLHb7tPG6uS z>L7AgaiCWLb;x&0ZPzvw-Cu<(sM8a*kaIOSNTMfdBSH;0P-vv*T30kZ11w{)8JFoY zKt<|y9LzEh>45M}`hOqNvFpZWO#6PY|F7Y7#^iE2pQV;p>D zBq|}T{W#EJf|9S#aFD_TJ9*bj3UWnr0^CkxP^Fa<6V|HRV<0}rG`rmQ3Op;;! z?AE>&*E+)q>;6R%2l8C-x;2 z7aRxUyD>lndfc$zp6tOvGB=Dq6&oDPaKlhOWQPM29ysz#9dXd=#K3_~3~b;I541aU z1gC%TKnJ$D;b5mb1Mj+3&%q1UIgXdefcPE56{5Wu$U6ci(60k`6eGMue&ike@dz6X zGiE**W>zO~;Cd2T3gLsz#eEuQy7*v0VZnfaLS0^ds4EkWgY6N}Gq~rILUNwD6yo$r#!XOBRVR11D2LmYV|AaIgNE0E@&B6c?gcG5faNZiA1}}*)6erx z11GliT0LxR?cESuIuCHIJ-z?e)^*2Kb!6eZ`wS@eHKYh!KpqyPC`FMXT?GX~Q7NH3 zq*$^Df(2a`HeGZk`wVlC&=8u*l z)a`a=WTaj8q78MAMt&zpn5pr!^*hAqHdoO=iDM)i^;TT(K&GB_*i{_HPFxH$#X~gU zYWKjsrL>WjtUnziO;l%(wxH56q9bkb!=Q;Ai#oackiiSx>#V#*Wt_ zc(SOB1Bt;*Aw#_*)RN`lFcG)<*apT9FVuH=gh++YsGaD#mlUlY5hIdqtT=&E#-Tcy zQ_V=C(rHM8uWKLm=kaFBneHZt!})r`(Hq&!Pqy&M-cqF6J?&4VrKogR+v$zeFU}Du zy%Em+ueTJd?#%uZSy7RX6r%nmPf2M^q8)ZJEerbVJ}9Sgu2R9pSDK{qpj2O}Sh!Y7 zX}*#-_4=Zz`xi4Xl0yC9qqt=pFsx?3?o=NHYs#PJpeG0s zqkS_6UK0_^cWmLHYpZ57byuC$ z)!xCh6-5Ul{cG<~Ww2y|&E3ILzHsayvl)w@5X@4&hcwpY5;U;ev2Zdha6F<=czv=I zD7^5Ig4x%lv1NO3K0?_snVu&6{ILvdNP9wqJwUdrcR2((hMrW&96~WewEt7V>^h}! zq&uO|-W&?;(Vr<~(Wf=`Oy(o(Kh5cYFmyJ}V-y<+$GfYvdJ0QG(rsZ#`l=w)L+NH1 z3aYeHFj3){DXnZ2jEAUoAg50BtmENGzeX#|tUIQ_cZ<9@v1**wj!aWv#!KEZqoI9M z;GG6v1@p3>)_lfciRfMt$aTqhSwTd9)#9FV1ajIO!)O=U6RXuxb~)O^h`&a96Kj7F+#;f zQYFCsb@5pD;&jjqPRFCFQ8yVVQcdqjkb-FOS7`YoTj90+2{7aM*Gw4DF#`rX#Jrp! z8EN(mblK*6Jd52k5I1%{;3XY;h-T5xL_L4+yRO*4T$2`kO4;T-%WNs3g3P==zoCZm$AcpGNX*3tcBIOu|#g2{LS zjhu;>U9wKs6KK6mqs(Z@BLxonA&@h_2kG?G8-(6%ZqKzTl8fqXN>7nosVhaADfCR@ zdPh>=9KTegJQ~cIs#LU_CX@rWFr5qCNQLpv;hY(jhB;wx0tXdoQoLZ3!a;W$n&JIa z8E9!zI(p%}bOo~|9r1qF9GTJ3;tX6_d{YNM+|Sf0hlrS|(3&+19(^N6!R(j?AKl4U zFvALTmKh^_HawbCsF2mpMxFDEWk#givr%W?YQ{K|e~a#M3Y~*8lIj%9TE=WysbH?n zf!CKcDwwt=9bPQ4dCHW5Qr((mnfU^uf!<}b)oM=P&cMJq-p)ZtCaUo81qR$m*P*ka zUHQo8jZ7ri{wkwA>7#AvnC1o3<5{4;-OlJ)g6~0|s^TyVr!0)UoI{+smxboLeT16w zQLmV6lwfs~gXgj_((at(;6^qYqWlyG0Z$@>H@Z3K?9pjyWfFQ$dn>+jI?n0ziYx9r zd$`tN(DYdp%-wNmP_un_kt=jxf?u#VVu|>fIp~1aRGEWM%*<=DiVfY%fk)zd70k?B z4AuM_3Z~|!&Vijc8R%3loKW_qS=Nzuvc_hm!KpQ7_)*%xihbc-^lIcu-#+ z>VD-u2dViilKjEI9AUVcdQ2FmKjkBM+Ye#DnP!@pQA0U+(F7+h(=d>wBI-6_!r80S zJ5av~)h{c6MPKTe)Qw&*K+es>DYg)qthCqL(BJL!)_f+;wAU-Ucd4DMWu%33VR(xp zXZFlRY+LRmi-%FWv)+pDTa771X=_F^S*lRw#Y%OeorP%2?Yfm{0<6K7xTKh3PmX zWE$Tv@Tg;-GJAaUB1(wDZ)iB|k1v0=M=Tm6=g5?UP zp-OMdo=f4KOSOVtT%*UO8b)U{Tj&doJa7ISKt?ER;i%!fWI zMX%oY34q40zDY za!4+{$-z%M@DO27IgEXI7iS)oV=oSCYO}7(KE0l{lwllHErwyo_H(+T0&9pH@9DMl z2a}y=vT+|MWYZ78HS9?)1yo?Zjp~$TF~W&M47jq#4!-oL0><=yC^Pc}QaD3ElW_9xKCupn;K7I^k{2ghqM%SRAIqv$=-(Ymtuy>?^ZDNJ$ifUU5W}{Kc}Gm zmm%Au7Zl9Ri%`t@V4(MYetA$oxp#>V$AB7m;_fnh2jyN-FcnwzMk-s5QubUOOyk|} zayB#dD(IN&@RnN@v~B;Tpwk|pBUMykyid75n6{2cgpflJ~;$4im#GPtn9`C@Js2X_Y zSw{}u8ey$Qdm+8ooz-YbETcNDAR8g2mQ5D zwhE_%wfLrPtb;#Z9Loh~>R`+{oO7}yW9yNm-j9P?2IksDf>ESkuG7hPS61QEd;WJ{rD8aw zI10ARY`dlylySW)oNL{jVi-oI1~}^32+q9SfO(`eii5Uj*fg>c;)EE^EQmE|sev)Z zIL5fqr;X^`rfD23n{L2%ma*zgUkAE8b&B&^-Na(6_>rY zPD&K6;6tiSDp7sY(T2&Ry$u%6z0Kt}+Tisy-;;4823*>D%p^W{IoPuvvCHA#95`*j zSoi*wgH;<4nmg}v@c9Gy9ACpYCE18_A3kFAlj==6TWb2j;7%`Xl;YLv5o`v~FcLSx SfDN7$xk>W3(zv={H}Zc`A9|Dk diff --git a/src/org/usfirst/frc/team3316/robot/config/Config.java b/src/org/usfirst/frc/team3316/robot/config/Config.java index 1b44fcb..b141146 100644 --- a/src/org/usfirst/frc/team3316/robot/config/Config.java +++ b/src/org/usfirst/frc/team3316/robot/config/Config.java @@ -152,9 +152,9 @@ private void initConfig () addToConstants("CHASSIS_ENCODER_CENTER_A", 0); addToConstants("CHASSIS_ENCODER_CENTER_B", 1); - addToConstants("CHASSIS_ENCODER_LEFT_DISTANCE_PER_PULSE", -0.07363107781851077902646820429561); - addToConstants("CHASSIS_ENCODER_RIGHT_DISTANCE_PER_PULSE", 0.07363107781851077902646820429561); - addToConstants("CHASSIS_ENCODER_CENTER_DISTANCE_PER_PULSE", 0.02454369260617025967548940143187); + addToConstants("CHASSIS_ENCODER_LEFT_DISTANCE_PER_PULSE", -0.0018702293765902); //in meters + addToConstants("CHASSIS_ENCODER_RIGHT_DISTANCE_PER_PULSE", 0.0018702293765902); //in meters + addToConstants("CHASSIS_ENCODER_CENTER_DISTANCE_PER_PULSE", 0.0012468195843934); //in meters addToConstants("CHASSIS_WIDTH", 0.5322); //in meters /* @@ -209,8 +209,8 @@ private void initConfig () */ addToConstants("ANSCHLUSS_MOTOR_CONTROLLER", 4); - addToConstants("ANSCHLUSS_DIGITAL_INPUT_CLOSED", 6); - addToConstants("ANSCHLUSS_DIGITAL_INPUT_OPENED", 7); + addToConstants("ANSCHLUSS_DIGITAL_INPUT_CLOSED", 11); + addToConstants("ANSCHLUSS_DIGITAL_INPUT_OPENED", 10); @@ -227,6 +227,7 @@ private void initConfig () * Constants */ addToConstants("ROLLER_GRIPPER_GAME_PIECE_IR", 1); + addToConstants("ROLLER_GRIPPER_SWITCH_GAME_PIECE", 6); addToConstants("ROLLER_GRIPPER_MOTOR_CONTROLLER_LEFT", 8); addToConstants("ROLLER_GRIPPER_MOTOR_CONTROLLER_RIGHT", 3); @@ -260,7 +261,7 @@ private void initConfig () addToVariables("rollerGripper_RollJoystick_InvertX", true); addToVariables("rollerGripper_RollJoystick_InvertY", false); - addToVariables("rollerGripper_RollJoystick_LowPass", 0.05); + addToVariables("rollerGripper_RollJoystick_LowPass", 0.15); /* * Stacker @@ -284,7 +285,7 @@ private void initConfig () addToConstants("STACKER_IR", 0); addToConstants("SWITCH_RATCHET_RIGHT", 8); - addToConstants("SWITCH_RATCHET_LEFT", 9); + addToConstants("SWITCH_RATCHET_LEFT", 7); /* * Variables diff --git a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java index a3a5645..921458c 100644 --- a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java +++ b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java @@ -43,6 +43,12 @@ public void run () put ("Left Ratchet", Robot.stacker.getSwitchLeft()); put ("Right Ratchet", Robot.stacker.getSwitchRight()); + + put ("Game Piece Switch", Robot.rollerGripper.getSwitchGP()); + + put ("Distance Left", Robot.chassis.getDistanceLeft()); + put ("Distance Right", Robot.chassis.getDistanceRight()); + put ("Distance Center", Robot.chassis.getDistanceCenter()); } private void put (String name, double d) diff --git a/src/org/usfirst/frc/team3316/robot/robotIO/Sensors.java b/src/org/usfirst/frc/team3316/robot/robotIO/Sensors.java index 6ba3d81..98aa17b 100644 --- a/src/org/usfirst/frc/team3316/robot/robotIO/Sensors.java +++ b/src/org/usfirst/frc/team3316/robot/robotIO/Sensors.java @@ -45,6 +45,7 @@ public class Sensors * RollerGripper */ public AnalogInput rollerGripperGPIR; + public DigitalInput rollerGripperSwitchGP; public Sensors () @@ -96,7 +97,11 @@ public Sensors () /* * RollerGripper */ - rollerGripperGPIR = new AnalogInput((int) config.get("ROLLER_GRIPPER_GAME_PIECE_IR")); + rollerGripperGPIR = new AnalogInput( + (int) config.get("ROLLER_GRIPPER_GAME_PIECE_IR")); + + rollerGripperSwitchGP = new DigitalInput( + (int) config.get("ROLLER_GRIPPER_SWITCH_GAME_PIECE")); } catch (ConfigException e) diff --git a/src/org/usfirst/frc/team3316/robot/rollerGripper/GamePieceCollected.java b/src/org/usfirst/frc/team3316/robot/rollerGripper/GamePieceCollected.java new file mode 100644 index 0000000..cedfd51 --- /dev/null +++ b/src/org/usfirst/frc/team3316/robot/rollerGripper/GamePieceCollected.java @@ -0,0 +1,6 @@ +package org.usfirst.frc.team3316.robot.rollerGripper; + +public enum GamePieceCollected +{ + Tote, Container, Unsure, None; +} diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java b/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java index 5d65c5f..2b40d79 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java @@ -4,10 +4,12 @@ import org.usfirst.frc.team3316.robot.config.Config; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; import org.usfirst.frc.team3316.robot.logger.DBugLogger; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.rollerGripper.commands.Roll; import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollJoystick; import edu.wpi.first.wpilibj.AnalogInput; +import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.VictorSP; import edu.wpi.first.wpilibj.command.Subsystem; @@ -19,10 +21,13 @@ public class RollerGripper extends Subsystem Config config = Robot.config; DBugLogger logger = Robot.logger; + //TODO: fix all of the private names to not start with gripper private VictorSP gripperLeft, gripperRight; private AnalogInput gripperGPIR; + private DigitalInput gripperSwitchGP; + private double leftScale, rightScale; private Roll defaultRoll; @@ -33,6 +38,8 @@ public RollerGripper () gripperRight = Robot.actuators.rollerGripperMotorControllerRight; gripperGPIR = Robot.sensors.rollerGripperGPIR; + + gripperSwitchGP = Robot.sensors.rollerGripperSwitchGP; } public void initDefaultCommand() @@ -62,11 +69,17 @@ private void updateScales () } } + //TODO: fix name to be getIRGPDistance public double getGPIRDistance () { return (1 / gripperGPIR.getVoltage()); } + public boolean getSwitchGP () + { + return !gripperSwitchGP.get(); + } + private void printTheTruth() { System.out.println("Vita is the Melech!!"); diff --git a/sysProps.xml b/sysProps.xml index aa4773bc2d25c8257dde02dc6fa9ee6e9ee14e27..adcd772579b63e33ad0356acea8d4304d0115846 100644 GIT binary patch delta 36 pcmdm|w@+`wK0$sn1_K5Q1``H7APt0*{W+{BCkV4_<`FVt1puuA2rd8s delta 36 pcmdm|w@+`wK0$sH1|tSD1`7r~1_KbB?9X96IYF3ZGmnrFD*&w~2rvKu From 90862cd3a6c5b42d1cd4d18bd044e7e159a06d9b Mon Sep 17 00:00:00 2001 From: frc3316 Date: Sat, 14 Feb 2015 19:43:45 +0200 Subject: [PATCH 07/29] Fixed gpswitch --- .../usfirst/frc/team3316/robot/subsystems/RollerGripper.java | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java b/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java index ff0b28c..f8dff92 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java @@ -72,7 +72,7 @@ public double getGPIRDistance () public boolean getSwitchGamePiece () { - return !gripperSwitchGP.get(); + return gripperSwitchGP.get(); } /** From bd8e2487b8ca6f279e6b7b2d4bdb1a863c4489d0 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Sat, 14 Feb 2015 19:58:45 +0200 Subject: [PATCH 08/29] fixed MoveStackerToStep to close the bottom solenoid --- .../team3316/robot/stacker/commands/MoveStackerToStep.java | 4 ++-- src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java | 1 + 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java index adcaf7d..4b95eee 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java @@ -31,8 +31,8 @@ protected void setSolenoids() { Robot.stacker.openSolenoidContainer(); } - Robot.stacker.closeSolenoidUpper(); - Robot.stacker.openSolenoidBottom(); + Robot.stacker.openSolenoidUpper(); + Robot.stacker.closeSolenoidBottom(); } protected boolean isFinished () diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java index fcdbe36..c2ed692 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java @@ -69,6 +69,7 @@ public boolean openSolenoidUpper () * Upper solenoid is opened only when trying to move to floor * Therefore it is the solenoid that when opened can harm the gripper or the container pistons */ + solenoidContainer.set(DoubleSolenoid.Value.kReverse); solenoidUpper.set(DoubleSolenoid.Value.kForward); return true; } From 8d70ba316857e9fe89dd5adcfa88865ad8b8f7ff Mon Sep 17 00:00:00 2001 From: frc3316 Date: Sun, 15 Feb 2015 18:22:10 +0200 Subject: [PATCH 09/29] Updated stacker height variables --- dist/FRCUserProgram.jar | Bin 1806194 -> 1807102 bytes .../frc/team3316/robot/config/Config.java | 10 +++++----- sysProps.xml | Bin 5950 -> 5950 bytes 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/dist/FRCUserProgram.jar b/dist/FRCUserProgram.jar index 56967403520a0a7ebcc1860934e6eb3f5a58f33b..979126e67133d974aafa6236d723ae1f8449a36c 100644 GIT binary patch delta 28654 zcmZ@<2Rv5a|My(;vG=%-EqkwQg|d>73Xu}Y9vP|BQM*^AHNv+~# ziq2V+QBjjoZIZyCQJ6K70mr09-$4ap>1CXos1 z!aHQ*q17ge0QhHH8_ksUOo)l;h8`1>YSs{oa8|de;KdZ14?>LMHhGZM%JEQU;1&;c z#&g2MfEgMgOU2Wa;l+B-wJZ!lo6jP~lW+A>hG5O=hs=zGsozURBJ1p5oh+R!j;vMd zISB#!>q^l*Wl&&A|;K{9_%LOjN(>*oAjo9AOpOo41nOukvoht#r;?@&WVnmEtJom&@@ z`S*U`{6i}%Vu#N~rR@vI{6Ra8lL@X}{8UC=qz~kh#Wo!LN>=;gAxA=TA!{e8ntUXR z)cBr#k-=nD<=8Rue$U}0B^-ILNw=DtPakPxWnv2FW@0jDxV12k@1jY;Lsmux;o=9R z&9TzyQumctl5J{y`YLJbM^z=MQ+93-J0q8FT>u*+arA06sqAt+om3ubsUls)7fs%iEVEZ=Jd7((t$Iw|->cvjL-qhVOe;Z)MUrah%!vTqQ?CG+jXJ zuC#PFopR?!GF&>@3G`ufY{N`&oR&Cigedut?5E#c_|FwXEN$ zjSAyNJFjsys*e{mEns;jHo0)nW@kE!rRZc?lQJDE;kas&BkNKTgQeZER{AVb8gKZm^jVKkbJtgH`QrLV zx!k8a%qoVZQ^dfumOs&`rOf0W-SU#f_-G~N2C>*NB_*y5^pmGset@fFp*g4a1V$v=}G8!vcR z5np;T)wucX{#*Bp%|sna`h=TBm&C@FJ6yM>%Rh3xCNmD%<%|TiztK zs2@s=OO0Ke?KyPncI;%Fr-RC4Ne5en_v>=YdZu_XJ2Uq=nc|h@2a6w+8D4Is+L{e# z#wwi>RO5=yrU&dkZ{K)Q{;0Ftal*Aqf1Vf3^cdLf%i{BFlfh2%!r z?~D!YlHAZnyRtnpt~>86zP{Y}>d)~{wrgy5DaA=Ft6k6(t12DwlREjw zZ;i$C=pRW7g*KR5t`Q6g>DyN4apn`N$<^R1M|PI}2 z^KjYG;WJgdY}>4~IK@0&oN4qOS3=x{eY>^&<%+6ZQY^D_v!+x=*M}4e*Lt|bG*hA; z-WAUpsoKPD9(eTrHr0@X=5Nab{3|}Vx6B{e5^{j4;@8Ua_wOXhB_uYAzkm8n=WJG# zP1b@pHSP-=3==xDMbeJfQvFuSjED~N>R+x*EO6C)9$J-{S9;>qxi#S~?3?KW{qx=3 zABc~6MsnKaSl8k%l@2!V^h#<%iVto&>?&VAc9}hA*md63o~#2AD_gEk1{&u0hL@eJ zVWE9*305uttn3`LR>Cjkfb+l~>~^`Ri+8qg`@9j`04~mZ?-cS*N(qGfa~n;XH+qz2 zrFuFoJ;Qr8Og#BuB>((^osX-z<>{BQt!_LxaV!4Dj<5s4{R)!BC6V3Pl4EYnr?-Et zUoM~RP+7#X#&)>s-NMz?!W++rxlV{hRR`>N+c%-#R(hv&q0-YF2fpj(8;1uwy{E4A zcyCGb)i0O-w%0Gix!z9C_tI_Ou@oJXvM-a_zpU@Ca)}J$TyJ)I!vdBn!_efnnF;iY zxNRC)!&eNl?N8nRbU`cAdETyL747M_dN-b4ScYpm{dP%H$v?>ocr<2?;Uk1BR{rf2uV~O z5&d#)t*lb3PVd%%)Asp?9qqi0Ql7q7_{~f6-nLNVLsRd!7QIzJc4qvXn3wl6;PWYS z@$s$inJr!F9M){;zz$Yc&@8qI;a57J*^V^_I%-=l-BFnMexugU0DGC0O;u z_V?WB!P;L!+}le`lkF(7vr# zzr;{}P8_cl*nV<@%UgScf>o!srHZd!IcRn>S9%TZMBiMb&GX^H&TWfT$0;Xs)*AUf zrtatBPTW!SP(IP4_41KBW3TlcYPH$IRPLpo-s=(Q6)CU(ito#acr$*mR(XrCv9|x> z$h!(LrZSN!^+l`y@(KsNMpyLKY&T##d0}95tDwZ6i#OirxmX&hpBbHRy)>z?OFp{u zV{YOZxwAKx`_R)gnS`g-?5_Orru*ur9Z{P8T-$H;_s2C{(!DBeG(KUQo!_Z9{Q37M zspFr*&pqKlMIjz(hsZHdEgeV1G`XsJy3aAWmP`}ijZtF{CVMDZ0G)|PEd&i!NV92PGo>8)e1 zKjm2`bxG<9G@5d;B=H+B_g2?eCTup7br~l;lLaNaB(z((HF^{zvc764;pIAr35^#pV$_!x9ll>eR2KD)?z!OGOiYnBawS9&=l%k-BeU)aJ~NX&>^?PH%XOT zCnHR459?@sTXwqX{P^n?u~m2ct4_aJb@GI*?Viqn zCo5F=D(|$^7n--m-DNz!!XEK;Pupe|lk^q&w?ex7J7qsT^n1obxAE z=fdXk7)_jB_x41iXWD$T*Wu32rXIG&F1DU>>_@ewG&4lGN=99S&)e5qIz5)wvXB|N zK77o0*{vg58oCq9#44QVK4aDgQ!Nx?moN7nj`Pb&4K3+2da_78q56pFC-0@pm21A< zlb2o3BPgZmc5;zbsh^50zq)$4{-29OOAPXrEu0+{E_`^u zZ%^(y!`i6FpH43izONPfJTvd>*URe#j$G%t7wBJ5cJy$>A(etMmls1_bo0c<0A)qT zmv4I?-EUU$H|z;CiBWEQWZtto%PG%&qeOnLcWs$NZ2g^guMZ`p_~dM8|C*3}`nGoQ zD7t(o|Jdh0>SEi&)3%@CdYvZ|8@(;}8=Z)`ESJA$ zPn6}iVXQHkYeH1(`mZ|i!V$s5^d+}bI?BaSZ$em+MBSlRBWkOXDo=^_yK)%aTlHiS zElR&6n(J8Fz+1^D&F7yk_V81GnmiV3^r2++n-jOrWfk1o_C+ne$E>cr1CL?<*~plEyPB|O^5_Uv4Kx{)Rt zTHR5TaCal^S#9hPbBE1j-vzNkFW=_Z*|ih9U)m%F{}5cGDw=b_LS3)qwPn|24A}G7*loA;I3(=+QxL+1Bcdck%korY{bMcaO zHU^iDx-PGNyi{)z&%Kbs7wvshO4qArTtJPk zR&hOi#m&`zK0+U4Dkm2?S*|#*m2c@jaXG5KY?y1}&$64_CJYVxT*Yi`xP7eLt@iuL z26;_QaDes5 zOSfmqV2NSMRO7%P_sR7gL$xjO2e(!Rb}G@AR*XJay0!C*hHmJixQ+cz z=T3?4^4%!;;bnO5caxm6-xsd?y}vUnJxCm4f!iOTKwsrl#)EU)QGR z^j-80{rHNf-IbrcvmZ(ysqU4hNsZJUABk&}D-M4AJn_xuC)9f#Pr_XHan6qmYhKy? zV5sT7-wxvglJ#DlE03StbyhgRG_j7mtl`11W4+&xop1Xtr!f^Jv727nz2sAAFL!wF zlC#kRRo=~MX?v{Cq93*yXO3E3xk-&@PrtFxB&1}YC;d(LCqrr710uoxz3QT8KgY%m z$Y-TRCi~U#Yv+k3m|himsKDOtxag-@k(5REt5m%*$*X%R2ic_-th2r4Qg>ox!wccx z*E6<0*j|#`_KM2fF@I&%C1VR~v-=%ddIt&zeFYSDEsN}-3b99hE1o~ml6!50y>X28 zLuKz4#eo?9uXK+r_UOB9?hba2MfDGA>-uR2LxlU_zfC1p4mM%hhC5$Bp8tJc!Tq-! z13r8jYIZiM9W@)cOQz&)Zys4zG7uQcm#Gx-H{!dH*D_m84bzp`QO8z&Tj-s-5jS-e z_K+XdiV)5=KapzFnpS>7w2WuyVE4lhp0abRUCr3C z*$&05VN5=li5e}lbLhnHF{L+@ z>N_t!+6R2=`A+K;OmN?#hu`&2vR&PdYxy}IAJTNX#X�=5f5%hN)N+q#P1{bXJwG33l`l!oT_6z0+n;HlRB?&_q-cG4&h2gIMrb3!H)wr<0>kpp zGR>bK$u!b+crNS^9M;`6Pe&U&^zPcf8IW<;WxHwK1`B?)hL5t4epBi%@7dMatV7lz zAtx^{GPp%Cp=2o~*$-M@A->=NB{kZbV=-TG7uVQPkDD^3IKkZRR z?o zoZMrAezgz%xxZwR;{%Gq`Nlgf)rR~h>yljtttfmB4-f1y>389rJe;hVu&Aj_G3@5a z{7G>%sE=8y4=FvAx4boQYjOV2*z3jS%>x(Z3xvm6wQh=;OfA6*4$-?gy_FY)LuTRhy-?%7$Rc$zF@9Ra0OPl&x&9w(v*)BiVF{m^;_3%=l{_^zV z6*qfM3>Em@ELc}=pF2?(s9U|*NnN`AVOITmvmys|(TxU*_n$qhR}aV$Di!*)qbSNn zNjkbgs@gOV&)SmjcPpgQVlBPAKRjrCT&Zi?z)Js&wqoIvbe%=&IA^SEpkeR65_KVm z&JRX=+t2B4w9Z*+En(-9!mAR0eJG3N^nrKLHqm<7tx;QboyzQ-)NIX#<20V`-SooE zM?Idc!L+{a!?F4zv(?-sJ6qjSF8I1Dp6Oo{YeQ=*Rx$`Zsvj`E_|DNolJri8qYBw3 z)MJf3jl5OC9ks>!X&agq2@&aJZ;TV`6)Dcqhdbj(200H@~a`)t$Q zpCz?9HrS=n`#gr7OG~ zO)mWzLAbXt}%oH+F4at+vZITAJ-DHI57uzN1*9%n#COaJ#EC|pV(&qLS zw)v`lyLj`xZ!WpnYc_?^+n0ZJuqYkZmm4`dNo)C5km*NHh+5OPK*xCWIW3htO=S1k z<`@sNoqAJg^tMUmL)=>*h-13?i_a_@>pr*6X}9LK+~L{{S3>z>J{>O!4WJv|T4Y(_ zMK4_-wvu~O92~=w&%{K8}3*wmMMC z%<1H=R|m%4oImA%g}VDp*NaTUqE?AZt6A?yI)!G(1ZW;#VZ8WGmQ69QP1M+)ib4B? zAB7(Z;w0Nww*OVXw~FHO(ST#p#p-%}zM=%a@)7+G4>cuzX=k!?>DLVQV&7$j#sU}I z_q{AXJf-AxbD52sCAT(@>e+iW;wvS0%kl3Oeywx7*ubztqQaYF{MXOyui0j?e(zd~ zf3P9V=tlK(1p|o|U!5yEu082-_c>7CxIgGz+uY8}|BZGitlnInp&}oA^u6Z2?2gJH z_s!Qkes(Ncr!7$VB-}N>->s|iuxo4w>zV4NBZp4}R?uDTb$3}`UN6!j>SHFQKE62K zGgVBgSHW!+w-5EjiHG=lIlZRR#0MSg^FqxI7QQQgwdGFDt1kJC*P7iljCbE>eU$Xf z@#&Y-So<40!;D|APU!8us@TX8-%gYgyda zdn2WNOW2*^$6`;m@%3(EuXxj;_~zuZ?UVLt?;ZAy84T?68@<6%uVed3y4m=T9aVGd zy`E8yngh?R3SNwAI5w}zIeX9dE5rv=ifB2YOkh#dzoCGpOY$Fj~l*8=APjVzs#-K5VhCl6iw~QV1@A>4TZ;K+#dQU_xVxsF{PONq$G(gZqE-csY7*7_H2HVjwW`5 zHfe2)QY?sBy2|=VSC;N`hth#$ch8%6VfDaP;mpal@Lc*$&AV%OsoIm$ zcVcReW;JnnWNm-j(VVNeC+5z??}V@t-@Jj)vS(F&pT~S|oSDeo+_;U>@ELnhtGs`p zHR&qv*|%SE2d(94T|;Y^FQ1Z`vuCKS z5u@xSk2IOBIw(q#B0!vLYLg`?%#1Tr?LH|AmGSDQHd~f*ig6wyUcRAlE1UyuQKB%8 zShahUC~6E@ZM8b(0OM?hZ1gC${N&E0P{!NU7v7l(v1X+oQABHPa9+BdU-)|0;Pw9N zZ6d?M*89h<576=t^NWe8a{uVk>nd!K9v|w#x$FE+*(vM3aFsZ{?f@=KDD^h9{-K*L zt5q)+hu-$S^;}Uw;AGGEqXq2=&;51z_pTY-R#*1@>E{oZzkj>(oPPB$=GvMkyj+;) z&d}u)DvvhzfwjKkOKz20S<#p1_`VYt^1PQRGU;gNJeZWCx2s<2rgTe)#js}Oz@zV* zl`nm}9D1{$*Vj`;)5|=>R`-$Y_$1qRK0b?xaO3cgCqG{HT^iPKzShIf{{9J__}|?l z+_#UN>wS6H^XUO=EIfWw&DDz$`lq+mvz~g9DHMB!x1}L*X#S^DH9_eWPW|*#KRY8D z-cE#3(3@;(T@cprpyl!DP*jw97J=)OLGkboD9pQ{$yRaNWFm8W&t~DatP6iuzPa(qNM*A?cV$HPg0MBl4bt%g_i42koN6TE z`(B>;{!DDClaFF2mz&VYaJ}!Spb;1%t{?`L`-wmQ?mcIJKuDb zqXHbixHyTZK53pOUfPx?C*1L7=eC4=sr=*JFL5VvbV1PHPV&cbnw8c-zhif z63d%q>TXAz4Eox&I+0N%foui#Od9>tAuU?2OkI_MBYsRe7+-@l9~ zrPXTcQ%+z!@RHhg{fR^0{6YFBi-MGh5LT#FoKFeIcnRUY6ThCs!1X~WSJwF;MbvGB ztJZ!nrfg#+-f!1NSW<3ajFh1jrJqdkEuy?&q_Wz4U^LlLIFSzg$I!B{qtuczVx%o} zfRU!{I6czL9Vz4+*xIfolpON%A;g(-h@nrs24BK3vDA$sMi#Weor052rr6g@Tx5m| z2@aGIK$(x49B{7M?iG|4W=585FUmDC<++-&ikVTbvu~fche8%3Fv@1q(JK)YK{iHP+bXq~TdI z#fqqKDK1`%$5A3U8Sme{nTHfAP$r$?NdM(74feG}j3f(1dU9GY2h?=m- z2~qBSEWIHz@mW5Hb}Qz6h)Ddhe(cxkUlC(6gWAX5zBy{#+ZFpW=5M+4-KVP$t-Zf@ z_t29Vnb-Lr^S6Ge{r%_eM>_U!&zgYIrZDj`T`}9U{AHQKtCj_Q_RF_&bSe~k%w=t+ zKA+yTdqUnw6!mMUe6$}5z5Nl0>8ckIqUMgDHr4;|>#vG&Y% z&G0*+GGged7iR2tI7%*gzn<36h2(z4#^&xrx?Ega()@J%R+-cUXuruGE9Y8i8&`M9 z+`MtawUC_PUbic|-W8i2I8@^IYU7i24+q-rnbFHzl^ri9S00KB?Yg&rafISzQVajm z@i2!go_#CsQiD?pe3!d#Y1OTIp&_AiwK>0_!_4s4$VK-U?tzc~^y1@gfjItRHmx@5hv3eWu~(%!N@mDs@Xg|ApVDJwABx?1@Qw!mwZb4;l3lKsas zlO1~8b4&JLz9t^~slGGnxByGT;Y->BylcK)U)kgOdoPE~cfs5*=LAIa+;8Un8kyJ` zvz)u3ZS#W$qeu7usJl7dJpC%FR)b|1b8ikBTlIRwZ`Ui=iL3g zx$?ye)uLjr3wpngeh}TfB92Y0hATJek9g*IX_DpW^6qpBYvfQk)kC;(*J{pn);=QZ zYWY77TTnl$PcrSIa~22=+ifX?qcymlI{NA6pIf}aY!6{2CHDABmvVHXL zlicL9!agnif>+(fHA@u}l{4neOFTQs{=2RF$ccWj`(x!BOF~esMnjdqvIT-qCqi zFX!!A_vd@jyCV&sUD7xoKlw=?JWJJGPxr|mxRO0zslAOVJ^J3IPul68+*I2^-agG^ zj@q9NOomhkKJ7nz?|@)rV$a_n_V;czy%MWid@1jp&4Y(7#ofK*Eq2AWb?&7@K_;JS zswTuDMHJ`#VHeQ3XX28-BR9f_MezBf)fvA>^Qq|Y_hxHzthp(0xGg|$c-9Ex*Z-92v8(a1Hvew|T2ENt`zU^p`|e8mkfcr1)A#%S>`c43soTqTo@m2Cd)D`%(GPl5 zU305m#95SheSWm!t4W&8)w_!gdbRmWgd5sCf|OG~lyJ`PR^iKdsG`)orgBQ*Fs0nn zN^QBa-+<%xMF+}hM(=L%KlW48jHyv5W^LPkBDceE6EF9E7A$kAi1|0M`5xm55>KDe z?`7AQ95gyUFQ{g-2dj5vz4Na(1%)~m?-zrCLv6N-yFQWu%Vw!ZcIQg`GjGHXU_q%L%z{`#XaBxwT7xH|s#? zCas1Va~svtcfWUUqc1gn+wPw1n7@9x@v-)nDb_hV%suJ5De%MK#|%Ff__4x|4SwwK zJ!%qNyg76c9pD_GH;3o<{G5Cqsrtg*rM8pDyCM9uW zV(CHpQuqQ!;@3Q!hBBmZVFoIb!c7>75h>h~k(eiquVN&2O52nvvKkhp%BIM&$7IjKmUo+@Fy+ zFOP3vBxnk_4Uy&gbC42=#l&LhG{f*Lemq!$>r%;t7m|x!N>yK@H!+V6@foR7Rpf9pA-BSZPcrZfW4DjFp}7WgL30iHo2J zO+1L9^+Er7dOqBj~oA>MEkqpMcV7jNy8{nH5jJn};J&O#dbFs~z zR!*2dU4xPN)6L{$gu5|v9XG)}*3T#&4`R`xxPTpaL<-4Xh zXO?9y2l{I=T?DTwSd$w0PwJ8zO%+YNAOxVog z`a(sV=F|R4m_uP*KN$k?Um_^sp8x`th86wI(p@i?_53dk}r0c>$C za4J%_z$F>&?q~s0a}3EX#EEjj2?$10bkp|Rs=}K=PAU`AqB%DIiv6c9y#QBbcnCp7 z!}duM5*3ubV7i40769ADVD-_51-KBSC%?W44X=PxN)WX4T+@9>b|LQ0C||bY$VyM> z?oY4*pWA7JvP3C*=#eST4+_L&%4qNdN~p&gS3r?gI2)3+ns!0k3S8*MT3wEC`)w zJxA-QF=5agNzJElAn^xab?)(yiOGJB{&6!>f6$o1i+z5wj{1ynkh(RCN%+cR$ zMe6%4!bKR<{pLkDjj|B&FUGA={~{b`l=ruE$@)0R?*aLj&&iM5A%Vp(j}hx7tP3=Z z;)r^d;PNQKjzUFO7emhyqRz!2vj0ycg;Z^)MT~gBmXf)2+$ij5J0T)M<)AI(vim2p z!}-w@TU?MKnjl1voTqcy;YtkF%MRE$w^_Cd?Ql7U2gEvraW0<`2_iFP80my_a`qtd zoEELM$F<1X5bVa4WQJ~gT$|An|DAc6n5^csM7k%bdd>k>4LAj}p*H>LDnhn3{j6VTDy3SxFZ!gJiamJ0X`|0SSGj4`q8ED)Y_s2XKPZQL=9Op&( zF1Q+deFlYTeLx%t zCG>y*#SDouQgs9HdKzeQW9(=b!RQ_$GAg5Iau^pHA{aW!WV?Zi*)kw*PpdQq=__#uOzZ*) zxIJ)d?0z)~I4@9y(Bxa38?9Y|v!D_WD5>cZYWBdRF{^q~r`r=}MWLR!F7~H!hMA8o zZ<+xt$kGdno4igknoTfQo$~^3#9K**cNLVW*-p0Q=2g&(dpl-;H0o}H(G?yH^MQ#s zII!jcDNFRmow2R`Bq-^lNFjb7Fq-;kh7m!z-nb}A^MPCj10?PHkRpamLuk`gnj~aC z!!t5&WVafk>G{Ykrgk;N%I0yB5%$IHF#As=NcP1SWA8psOC~5TqQ6=OQA2km@Eo6|5s7UI#37^o>7oQYu7=i@QBSYJg9XY zZi_vUoMG4z4~~hW;84PdKQ4{!k|Sk|c(0SjB#8R*qXB=g{X?FVNeAFgSoORaMHSQ# z04;D-nPhm^<8GLn9s!~-E@R@Uh1PC>eF1wQZiz{n%rN|D^?Yo)ZB7J22^(x?$$key zr~I^^VU}PeOJ;xw8s7kwV|FGP*C5;#Q*ZT>EzlgNL&4dzels#b z#1RI@7YEER+$bUp<}RK{ z0t&K=m@5-TCXo>I353i&ij-{+$AnRL1UO+IJ;U%Ky-08(XyZ(Nc9a{5FTfIG2u1@{ zMqzx2Q|ey?g~ZN@!MIJNRzwuE#GCCTcpL@s?U+OWeYArP->&_a|M3otAFa}-abhob z5ei`#+KqZP;+9BrBd$wpemzG9To53m1&EQmi^^A-M zH>7u_$Fq*9sfk|vY5sA1yXHf&jg03C037?1V@uY9T-f*3&wzmITetcLPQZDkeQ5Pvc($y@Hs3H#l52?ZP#?1GW4-a7->kxMtmjiyS$tn!07S@a%}S}qSj z0WSxI{-<*kh6hQ7zfVD-JQ=DL^O9sThJn$ zJCi98$y6p(l#1iod*R)d)*p-)wY7lS#yw!Xg84tuxjoRzEL{HxYpk00Uz&;@b1`$G zQPY~|dBPHUgfc`2l zvm@Dkpt?$vV5HEseX#Y5+6P0@PH%=W#&(;KKy*J?5nMQL2rv&lJP1u4?MH(7Y2apH5D7BUVCwrCP6EkLXdKsv z|19%DY1o-)Qs$hF8)7+eBxu^m%#9wFKu_Hybj%V7+5=ny@%8tNQNry zkNy`ouQDLR>iwilDHB|g%^-jjT6hrZwOtlkEGLsF_%KO#Wx^&YJ(r9r7Nnd#r@DGM zq?Xzt+yWcOCjbro$oXeUq+pJ=Y!RV=BZ~rN9`rLA{8ulTqcFdmRM5^b^}@~jbIdSlT6=X*e9>< zB*DUL*mu+0nfbFt!Jx+xFeu(LOJv#w&K4el>`eD((eI8x2k&?^!Ib3cj=>k`lw7zz;K+gbbBv7y>vF)wT3!Mupr>3c!o=Lb zk6z|L0b1e&y&AhuBgM~hVXaBcg+}(7H^W$BW?Ce$$^%oe^GR?#59Xz8V-oz%gBY?i zCx9#pF<}v%nSfYOLOzt#ZAHjv=xjcm2Ugn609M3(3^${=pmWEd{!#WU(&&jGu}4aQ z>G;So$T{VV&L0CG-!3Db(nzZSoG4sLf+lws0W{wKZ?M#RvdkWaH@!)%kpl2;{~8jU z_F>^6M>nhA9BuvpQX#Dn;-Vsm1mlI^uSpmIB$2~$+zKm?BmfPS9fwIIDTV~cqhMa- zE5g+%awxM1y!0%B*lpZGN~?-sTsUke0s9Gj5jK>JdQL)rM4f;^8k9-^Wz>HHTC{FI z35-tSCYUzt)=t8{tMDXr$>JOW_+mOmNVgaoWM2vK)I?W`p>|tO5kL+Vma=dn=@N+3 zk<)~_Bnm8nBHYiDK$cjt9=?Db?VA#4+aH%_Xe;dbb#(p|blGtPxL$IH z1de664HnT$g0p3?x&8W(1pMXTgZuLtz=A@`VFRA_dKTl~3En&{hhh(olk~YU77?@- z{hL)RPl0Um3n`<0f)*vuN{mn-Wa>W%*#_*vFH*;}0!rm$LIO3gzN!CV5kz?vQ1fHV zBr{k6?jB($fn_Chmo4`UfXiwgRw_DO2`zhye=g0BR2rb2HVd%Mj;3T`QtP+?s}S1$ zi%>WXPW=%lY5ppRSSe9fSZRszH9*Kxq-SJ?7{4M3)>gsjuTh(ku%gB)2x%4_g27Q# zG`K}O13G8)XEBLqpc^%fXEDzSCenNsbHs#Ibk@=lbQWBQUN}pk>@0+KkL@gm_Z+T| zeRZ70(Ck?S(A9RRLhzC~^^bL)rIiaZG*$pwVlH#E?5-usDYSUoJNAN8W`PWa2-Z;^1@5ts`e2QI30re zt8{=*)tA7EQw~YLy9Be%E4XwbGT7C^ICLu_!EplYFPY9=3c1ly zTSYRX6|91Yrw&TEUk4?uI*%sm;Nn1`hIqm)=>_QWNHu7yq{|>yh9dwmqWJ3}q8l!Q zr=>V0H3!% zoJ+&s6g0pr3fCKrFpH`-LYs9xCsn!|At+LBz}%JB2nL_On4!(E6Ypo4QM&?eydEQ& z9ao?gDW7HlI~utHMpu5D#h71(NbCDaGUMM_Wr$Fi-q|%=g|e#uPRp*soOh2I>0ZOv zVl)oosf_Bc!D@S&mjn_`0Dkc!wT3dr=D|GCjIYN^r3g|M-NxB?&{W#L z$*-mv%HfwoJfnL{?XM@v#6m*RLbr5stkaW&<=#x?d0?46uT{ga1{u&vw z&7QQZjR~!_n1&VcR7H&~;9sIG0i@9}8#Wvb%7JCjB-vc1SJ>_8=&Ycr`(8`ej|E_rNH$hRHxA3ZUPzEa30 zNKC3~SY+v3ngivZWP@8K+P}TIaR=DctC-OeK`a~9h*Y|a^$;{fZ{p_0)L#z);E%7dV zDQ5PV1UtH5+p2+d@51H&n=afQ`!Prgo^(O$c-)0c@b(uZ({LA7oj0$hjda7DXz-Q< zuCLfsQJ2iW{od(rsAI?b8JQ&d(+%P3`C*2E-Q;^VNfglo&VL)9Mc4MguBznAEC#;^ z1K(;;6@uh6wtP4oS;sv5O&YBcOA1=QvtyFr&bR?&z{}qO^YSz}R#az1E1GvCW28 z9&l?+I2N^#U4+x> zueQu7bYdH!unf!ENh&Hmh82o&DIoO>44>akl!v3PBzAFhM&;iq-%7~7r_RWzNNNxC z+qJXcP(LAaO($hM&taThLg$~u4Z@QQcE;vqdiKeF4tf+s>Pa64`;4oOF9iK8mk3e` z^b@hmA?*>cx@r*UnnIFJAB4F);3U$00j|9sgbDCM842zdLks`AJz_zth9FnwSyGlU z1XE$u1ri)Q3!TGIl$EBzF>V;9>D!kHnKXKL37mntOb?ClVK6dsm6VkY!>(MZl>|O* z>@sL@Ee9LnqZ($`F+(d6O90%-+$9)I#NP?6!>EUM&z$BD>?0JyuppS12*o=upk{v0 zNjoYpVR3mqjQn20=~(m)LDEnUK}NwWL)87?8+Izvd<9z$adiF_xNbbkPTm1zzXGTG zKapy8UO^~a`9^}rpJDXET>w8~o1Ei|z%NokYZBU!iv`9SdJRS@r%1Z2h|7?=MX@2 ziGOn^Rf=Qw^dl@wYAtvN923oxe@!xci`@k8t<3 z)oYI5${#`YYYiy_myNJf{saiX#DYn3K_Fy+vba%`76h~7I0SP*6j{dZaA;_)Zjc=x zhdm8XEJ;5b2Rl1A5kL~&I&+AUqt9ys%1YZx(D1e61dJ?GIstIhvZG>f=udwgGa+*Vkp!w0y zFJNrm#Tl6$=2b()qXgo-!oi1nw71`& zfCDWvG#{#Mf|@Yysz(SJSKBO^@^@&2bDbo!<2#H9j~)^{`wn}6_6H=en1tn@{Rs(j zCSl@Q^PB`9CSiv7G(-a4=iohKL$@#&Hk%uMK*vYCCS`d)VC;CkC&A|*(A_d)Brto& zAx<8c!heE)pTCkc-)D|_lbvzwkZ~l$zc4XmP^maN{u?rQ3(TTZd8ssl7C;Jr!21HxS+YAq)aiyy z`2&t_!Dq=Vr*L8NE{G;YojrFb$zpbE~qOO98XlX<7=jH)H}OM?K~ zi2fI*v<6)Qti=lF6HjH-WJG00-TG8EvZwbO&9RehI-|un4e%eSqru+Cl3?Y~GczhL zx%UyG01cm8F=$r`Z9Zn;K!Q^gngLeeL;xCUbfCgX3ZtoE?QR5vBUg-O37;4YVKf?A zvW&`&Ze4_6Z^gh|hbO7>8v_fWJ|u8rrkPSC(GW9D2DviR*wATakoNmet1{C}ux%Si zkQ)GnP4dC~|9!)pN@1a-f=m!qU{({hu|T0A5u|L2g=UO>hkM1pFv5hQsiG+33^=xl z6?B3VNcuD@Z6S6(kp!KasUk>{4XQS_bB19@{B)`qq7$^t9+EaohK^(0MsLZODd2 zO%FTQM*<6Oki30Nf(&lxMG}0J=Y;PH1tG|sRY@j73B3C6G+U<1IeTikph0RS z3PI)H7?MC+7+yXP3ej}19*Y^q3~O6F12~c4VO)rODNrE{PDMMDvJqjZ-+fmC(9l8= z=(wB9NsulA;iv9Ng0~_N%PW0IU?)nm#Pa<}Q18nrNX!fT=!PiRZ4V^rU!vfjS_ld3 zH*kv0TH(Ayq0alnXq;GJ1gVf5%E?&$xly+T>>eJ9(Il_|_%wtc;*3We;>NEfbxdfo09W+oADVzbUXn+QRaQpwzP2aAZZyW=FDx9>1gE?A~spmrwWz! zIiaQBNou*aL-@kDRKqsjoncszxGYp*;NC3e_gyFeUUjNrKl^9V(sD4jcgaFDP7ckb zjj-;wBop<4lM5xvfsXsc32pi;tGh+i4v>#jBzJKCxQ z&3s;Oh7lrbVK|>__B622giu()TxdRRveASKzU?C}Elw#zeM1*=A-}!M;^>(&Z2>dS zA}%Cg#ifOuRiHXfb__&Ap^G37oT$~9dmI^*1o~jdB}ncjL{-6zkLxt=q)M}37GC}z z;z5>f;O%8q$erfNh1_;PLU4^ay?1}62Ia&D z%vQkFVP7B`hFsNY>#*)f;;D+Bs>9I!5<>tPWUK*=WSl^PRdI0ogVux#t*s>UP6G^d z(~+zu&6|1YE{1JG;;RpS)S?N+b)`(V&bwV)a^&epRSWnpsSI8W@$KPaL%Ds>p^tpI zXSe$cKa{RTbHQ5tk((|}Hd~u!h#3d|OS7Og{@gsMLk9{<(1xBZ+VG#KP8*ym4Q3FC zR|lpc{fz`rK!G|mJxV!p)uqitUD4dUgaI{7AfA-sx=@B#0s-7HsU+eFSEafz33%*6 z6g`?Z#+FJvrBR|DXa*n>^ytByky1bcWqp{-3r~`u={Wa1)Ex*u*6D+fZY47`JNlsy zL$c-cEXLIUicLK;mk~zK44^jO&(EdV&;moqpLYpG8`69+F?cy@Nb|w!t`bhe_Qwd8 zsizIx>)1`tycU7aJKnVg4;+BYx z3&`52AkZR<2%;d!=E5c}*dVg15tJ|{at(7FJ;x+Q#qEr7XVe_m7zsq9qqv|Z4l^2} z&P-z5X1>?2trX|vSD){@x8A+)zO~+~3o2&cDXl#_c^fXIpHt|`Lg#q}*plw77AJq~ zEbsaR*%{l?7#~E|!3T@OniiGb?n~PK^wu`9DBD)W1Wv>v`AVl^-0XA?dZtuUuv(& ztQ-6gws|8sv1%yx8!3Kp<4^A@jF$HKAuh{CshBMzb>_=wst#W& z`=g}#$&7ZUJqDdfiFv3)8`DmTWV8oK0kH3BWFSGPjwVAO2HDX7bf>B~4x~V6v}ZAp zDmm94WQQ`FlPW=s%__~$DMT3Ql>Eyl*h3ga&{7c0Pu z?iT5^G%Oe%KQH5SUa%Y_JgroKNOC!B;G7vR))hMS;Ow__3e^V!6l{W5CfHmdq zf{{y;@Ld+Mq z+(OYtxl=IbJ-Vu5+NQ|kH26L;6aj}yu#k0wG+_WGq1f_z-QwVKC~7+Pdj{qSem}6^ z(UgB5P2ao?VLKQGKaTx_(cTSH;XxNx1BZD>w7wkpZULrXw-z)TXB_f&ulHEKjXJ0jMScZBRJ+<2dtbj409VG3e^%#$6W$ z8#~5xS#y+Z6wdo7z=lRn$D@aRIkS8^MwZ~ufs3!`On0Zldnu4JgQKxHd=kk)L9`qy zyc5eoYcvAU6sG_kjg3K{oE@)Xw#H!MpPHyJTFQ?Xt?6?Sf%ti*s2(tyB$ZZdtUOwS zgRoc(m7TE&&;2x&)Ml<|Su`fbp`wONm8>{U4j1CG6~>M_<4{}om5gzsQB`6u@|l4K zGnA>Ab&T0mp<-^%K)@GPtC-pf5!p;^sY;25)xNlJw3KN6c2G}$W%R4}Io%nL0d(vm z4kpY*6}mPv;6h@9XiK}3QO=H;c%bn!Mtji7?dYH8O;fJ~(6>Hkbgbb1H~v(?2{=v( z7=zI#IrAg|4R_}>RV1Tc!HKZ&>I?@P6EWoOU*h0yBAOuM8xFi@p@1z{IXK!T>Zmjl zoujY@}IuP#eywFl;|g#z{kOYYu)&#-wiBn*k>ZPhp;E zIoOv|tXyU=HIQT~elWJp6PrTrvZ`b%HQ znlI5a`$_7ao;EdFpz`yG5{_HGcZf=!;K-+_#UL@M_QbT-EdGQ6taoknoj-|``cp~H+r5{GDLjo)DICngWaAsBV&rVhMMF|m zOnx?W2>V}4vC)DiQvpaxm?t5(gALjI`6%9q&9P!XFI{qBAM;zL%$kgDZL|rS>PG#_xw5ZO`>ZY27ZL~$zSGc)I0XPm_fIbm#QZZ%AC3}`(g^ZV#DmveUm%z=8 zj$C7*t0WJVcl{T^{r0t7_NH1gzg$|}F)>+F4U-M0lZ(*jtJibjk^>M`$3T)$_#yip zOszTC9mZ|qz&jVflQ^i)#n>`zVZfapGs)hq47gEv9wc8kaq!blBpvL@gR>v*6YBptnGvMWsHdR!%&as;7aX}#oKfc1H7 zvmy%?j-O;;AWLi*LBAHjnJZr^Or|j7i~>f`o5gU(bV0>b6{0FWUn$HmDnE}=r7MOX z@)G!wgB`Y|cw0(df<-Lus)||JhF)}g2`YT`nu;E^6vZC?yNc=f4vI;K-*)Nt>)rav z!<&4FdYcf5uBF&7#oSUc1veyj%3TI4+i!QLkvzPNEn)XmbnqQS%VjyVtsklA=wHy0 z3YKFI82zFXF?C6`zl#tX9M_uZ z5i2muJaFIu|8EEn3}9dgIXmd>=YR8xdb5K;=GMdN7kD$pgR z*wrRd!75B9{Pcl+tpbN-<~ zuGQhEx1p3W1Z!8>Lpf(6T4JwB?U@~X24SF4wF=jw0V_fJ$IXd`^sT?ew zqQ~)N5v-cerG|xdvpP0{RU0q6EbXVX0!`j&?9OQEVFiv2cTDe2+tIaZxetFUUQmhJ zdfbLcltDwDMo+7iNy>s;v-|sACGS@7XEGQka<|@=KdVz|z zuEq&(-vcUUel;fge;raWE!Ak7kfWSI7E_cUo=|`zZCj1r;oGb*b~N{xzAyW`9C~tG z!)k<_B~~LmYEF0RNvGCeu8%sd@2?ueRZO+!)bFT<3ASf`ht|=AwXp1hL&=O!mbt%a z9o$R8$tIH(-_d)i){KEQkhMSHvX>qD0V>%_CM$f%Wna|D5kd=I!D{6U;btfM9Y*!F z@OkEAu5q^((J$>H_c}y>m28{bb&pBANLH5<`Bey!NO6|WO z^mvoT?MfXCcfDpRvwE!VV^0;2^se;hIytmQWxwB$4cUDF`&C0I-~-u9?CjCm<6)uZ L9l^~RrCMhMUP$^0g8l;3$ zNP`k-l2ZKZ+@t$lf6sF}`+e8iYp=cbyw5RpD&lK#1i!OAD;p0B3l|H^ac;*0{3@)+ z;9>ZL6;Q4KMV9{5p{UZIUKB0jc`1`pK%pm8Sx=LRCv5&?!ib}VOmJ|;l8FTF^8)nT zx^oxMGX>6#7o;cNDyQ+$B~f~$q*Tufqf6Kg>dDN_hHuD3g%On$-8a5MGJ8xD$pp9g zeKOH)5knCM|Ez1GSaM&9vasA)z`~-MJHRHE+ioO+rj>DyOBt3!qVzIj){u28SffnG zjce5D&o68A=uZ`QBjR}}z}<(9NFagb6rEf%Z=Tr^%N6u?r0cEs?q;PYjC|kH6G+ez zGU()T<$4705R%-W0DHQ|m4H#QE~UYw>ZPo(5V8ut!z1XWT?*Z-O)^KeBx2k|rHqOc ztSGrhW4$iz*(O5fFNocS(JLHxI4N!s#=;WF!NRgG_g0QtZpm&n-U$o#>(OUMLok`OoDHJOY;ve@gHKj@C+UdmZcNUCxZFag311KtBi zgeWX5Pbg??0cAc^5Wn;=Pl?R+Gyf9ZVD9+>8@j!p1p=gmtLQ!H>aAPn^6s&-u!Qrm zuox4r<}bp%}Pbv>Io+n*8&}2bZ>1^sDdx@{fLN{aZV!td4%L4F3F?aeK2Z~sN^U+SZ zb4OD<#c!-QVcWMa$1p4B(7A_L)Zx25yTwlHR-e4H+`rAeO7yhQv2H(`GzCdb-}Rmz z{S67M$(HUs0o(!H_AJVKj#Q7DY-G51hd6s#_QU{Zm5jqG_+x~ zIkC(7S0{9_O(~3BYoKDAc>b*J*G#BkeNNN<4N&zby8dH(qY+Sc45F%S-#S zs$Vo=1-t1bliF{cxlZ23BXOKl$&c7?R<5RE3A7hyYaA!F-W04+8kSB7-y`#f@Ar!S(1cBFH@EgLiPs)mpCHS&ON`B8-aQ3dVSjNwhiu1e?`$F0dH3Xl zYvoRt2q#+e;PcDe+k-9UCpK|y=El{7X@^U`Bra!{mJ3cSNlR4XF4PF#S8^t?mCaF9 z&%2$^Vj;V<%8;DJCAK`?!tnB&QAOj|9h{R(7AL;rDO3)=S+d-MmrYabvTgeY3wt){ zu<~7<^JF)a?;07&tGVVB>)C#+`s1VG$GaZ!cx)`6I%zr0{X6aa@1p$=4_8g@-Onx^ zNGqS(cya2|s=Ool!q!(szhniU{#m=|in_Gp9d4)f#uZ90FWRb|D&?wnKYnSIqsW|J zqAd?w9nLBiI-F8pk`ta6qF)v8<#lqZtCA>H)DXo7VN(Zy!Vb~D?W_M@|U&bj?s!+YhfSpNy=lv zCEu@>ItT2k&!`{wIGYl5>f065!?km|dOnaIM#{f}^K#un1H%tXKGQq+=F>yfFZ0~RgZWe9M>~D%W0u`> z+NIpNDoHfPk2A<^(V|~&&yu-LoRVuF3O~!uUdWZZvB>h6xn-?s`)htqOa0N#SEZ3E zLhA+ugCB@ah6tq4>N5Yd(_;rtf{L%py*UeUCZ##XKXiqIr?QN zjbD(jt7_@$F0=Dac{(Dfx$?K+E`+eaR_t2igqG;-9XK1{|_@?cB zP3BuH_gdal%zW^(tWW1)YX>pWkRHw$4z_ zPx#om^(m$~g$EK;!U8<%#cI|FZW-7W+5ONkcQ8DX)3~%q|F8bjuX{#bX8$--+BfH! z>d4CthR#oDqM;Aeh7y~bb1&W+;s0jLZLnxEY26a`%WIO}hsF5{{yr-d`18po`BARi z>rL;uJHK3i)^s66t&nGu)|nNZjdq6X>IXPJewbMrnV}k8{^fF^-bt-h9;dCJ$1UTY zpZL6R$8J@DWv`1&T87;8Kc#P4o%`X+HlwAyl_9c+pCyJ*-MN^lp?Lq`tB~^ba*~~Y zLLTKTE%5Ih3-h(`u=EeTyzsbY#(?$F)UMX(1;XiPTCNOqW?Hs?;kRgBNOM2(On%~- z5nG?f);L?B#bBgy&-ls=dCY^jnPU&}O> zlFz^3@b*_pVJ%_Y{vF;0--VtkHuHPm_%S_v<4VluE0)VQXv?MqpFFKB>R<3_RRq_n z&6zTN%h#7#mw(87a4anO$ET!{yg*u}j-tqlE8!UdE9>%`L{zU>n?6(SNb|3>Umdr@ z*rb^!`plQxC+)0-^~UjmJpCVa&nN5Z-c5FQRjqq)OaEr}b*=q(%R{u6-||>t7%5kH zaVzzxgHHwE)uT7RbM?Vi8(>FGn)zxp(M4(FOM9thl7e4b11{F#ui-&X{G zt&T0aocZ9X>7M5-pW}zODE$twr9PR|c~fi_6i8b?FXYTQ!It8>2q#--srlc72OJd+?uW)yie^vbh0^( zqP{O$LH%{X+E?ga278i;l%o5IFIiR>*xoNYH}p0xy5d1|`mu`Ou15)&^q-4sM%#Wi z`MCa=yK{xY30eCL&7W_!TzY+0#^k9|Y|Nar&~06BxA4b_(@F;7fL?KT=>sN`o{TD2zNP-EBf`wjfPAMcMR^bJ_w?7K59 zT>0moYt>+2a7=HaG%dy6bkVtFzYB*J#z^cNZU6hK!X|KFSR<>%tHvY$l%$(}w0gvo z9aV$ddXL#ui^hEQUbsVKN7;u*?;GAlH(um#yc9e!B2{_NeQV2&$ZEIyJ;}m?t%l9M zbJt5;l(2VBv^0Eu>QGw1HRZvo{8P%`_*Y!Ez1o%YxYpk0PC;dGvlGp_Y)6K3m;KS` z&+oSRy(!#xy`(qYZr!}Bh0+?~(4CwnK0o)IQlasEt5qk% z&K}I`anw8C?R)#f-DOILoE`PYV$i{?eQL|=w9e^79Xa^hx-eM$XSIjTuJW{x0ij7xxop>-u(GjzI?u)Vc(&C8 zkt?>Bt&d+3xw8DS)A6Hkf6-2Ue^+MwVY@2-d%OMl9eeLjro0|d3TtybJZ`MHdgIo6 zy)o}nw);hRSiOx6&oL_crg8UVbh_1-x^bG7%xG(4v+cH($6eR$Fj}%?ZooOE=V~^i z?u!eXuSV9L*|H(xRq;XIcm8Qk2V9P*rJZgmh`V-pf6%?df4o|E9k6dHxN0zlwEnby z`Wq(kQ1{DKt;0dDzj@a-+>y8zc_2-D+dz&+K6{#$)sn$&>rz~6+i#uHX*w0cE0Ja> zk)m~uc1O3){8Z$;j-fkWGMpM(426TDbbsqRy|0Sr(6$QNVqwTBINp&rQ@-s~N{WVF;|sMO|SQE{Wmcb@U~CAIr$rcHmp&zI?c{v-QtLaL^g@rHs# z8%^=p`&Dc!+y$C*^H+C=hTM9Rf8tABfato*{$n|B_39!POKfu2x^+Fj{7doMz`9Kz znmF@Q$Ib+3n_jBRc%->$fVVAmqT}oQn=3UY+$7UJA6)sT#G!eAYkZZ8y`9U(kVCJP zi#nDr?J+-*=d0;@T*^l4EgxQf*nTk2zRdM%p^}QhW2?7Xh3AaTSLK~9bBH?-sJhAJ z>Q~*>D(jy}mFK-%n;vp=tH|ni)zoJ#Og_AwUUEDZH1Q-@PNxON&3T zlV>4|(S0QI@EZ?#D0=a`ojkb`2T`QG6z5_bUAc(E{-tlztLS-a>@do8dLG2dLz$!> z^L+Dfzxv6_!eYjagm@{|wD1_wWn#OOG+&NXnRD&qDx;{E7IlPsyg7A#S)nwhi9g{bvp>*`ztYk(0LDtab2+-BO|LPTtRRcZ~L;pyDMzAAahauAAU( z;5U98DO~m(YE*|TT)va#ca$KKdA(|JpE#0?jsAh3v!P&ttsZkg1 zCY5$>Zpk_GyZUX!+62XCmV+ndX!jyFUh1n>aGL9=-s{({Ufi5?JTzHe`R8U#WZ`te zaSx@$Zp8x8H%h;w?nIidd3mMSy)-mV`jRkvR@YipyV2s#T!+5Mg_Vo`F1Jx$W3^z* z(3-_YKAs$xhicCE>oyKrH5Z=zofx+CV-34J58tpD{EtX<(uO94 zWIxnq2=2*0F*RpUu7BOZm;G)<%U#EEvyOgA$M%KadZx>pH1OT<{)cEq>F`MQB}PV- zk`FWM-g;Dz>^bnZ$IC_{E74nehr+y_kB0A5i2K*n4!>~v?vSefX?xyhtDbA(J>E{0 zCb1ium*JmTA@BTjL`)=QNhsLgD^X+?iYEr)9QAd=cz@XcNMnRe@Za+gj}D>C(iF~{!(U6J4FBF7dui8jd}^Z_ zE$Zrz{4>$AdtI)&ok1yn4i~uArZg@o^j5HMy2Y~ZSDsC+W6hgWS4_)3ys@{uYW=?T z#l>HjKObUUck-%JXcylOH=!%%D_?v)UlP9PPL-ZVhvZ{VgV^04Oq6fD7Ou2zz4rNf z?{QDxKhqbj@^2cUA}%{kuIw7qt>D&+-`6WN5aY1Cuk=7cZ*v-}gY;6}1s_dI1xxJyzA^pIdN}8Ih~yUQ zkMQ5Pkfh=kr;nd)|9VT(iofd?lsnt)T544>fQ6f~vhp5kRIBh~RVuuUi@uZ+aZGz3 zW*f~)6Sc}~ZGB%nctf{JNwA;8sefTw_9;V`KP(o(anDojMvUIQO?c3erTFxzoGIbB(P8Fc)oR+^_0-3A?y0I*z~5r z-LXXgZjH69we@`uZ~W~2T)bo5 z&)zNTca9`WP4#Gf16 z-f6AdAroAtX9xTyY7-~* z&)rp?*TpGjT;?lndZvFB{%r6`&V;1uElVEL@&Th*HJSVoMKzhck@v3g>#FykiS@cA zx^kbk?Vntp;*NG2+lpHf`g(0!SEx_qq>LQOc6f9))_UJmfcScsFRR7hyBe3j4&}L7 z(Z87e5%18;>hNnvBpbgutSI^2@7_B0z-mqN?tx4$SO3G&&!gF^$BiP4ihrbNbbTAN zj94&Q)D*mB%aifiVLqc>#%xX3jjBGpDtU3c)2>;jssrHsj?!cc1;P&R=w9M|ptft|If0bEDbjYftAYbg6IG ze9?PUT3YWVrNvpUV|ZRB?f$X4J#iZf%)%a1i_kIsn)oN~&jd9M+alchx=(HHk``5w zHCWJNo^tiW&0D#F9h(j;I4m>h^o#hbcs?v|sYHZsoM6xV zM+RE%kGz-L+<%f>^>*3m(q!usC2@_NbGC3cst!79@7mYLuF?kVQb;eS26@09yr-qW7%`L8~1VySr(dtj;B0-wYiSN7y?&3z|h zfA(a~H#>-M;kJ!K{$@RV7<> z%>-8Qx1|dfS-0lwE1Y^&Y2UInf1 zec}C+6LGZYQ}xc=IEUs7W5bDQ0?jRlQqB(=Oq|c^8~AB7wcCux>uP(C^jh`YoSsXx z?Q7JQz1*q1yyb+^)E={iFRYFnD>L?|3}|D+d`raj7f8N8C?UPMx9shX$1chN{A=wj zi@Bv~cl+2DZIzPRyY0t_lhx0k{8lkP#>b_#c-AMr*NVZm{*j(;|FXiLZJU-ZTh2oj z@4T^SqsQ^?+`V5@EUWtTO`f2HZ`zWt zrUP5=CGCGN%<8lh6Bwv$xKfeZa%l8?h5n+zYt4d@PX`Z=$Ez>iT(_mWzq4R*)x4)J z3H-=n>x;qCVcE4j!NN{A9-i5CR?)fsyXET0dAI*Ox*jB%T9x*TX5pdUFImjNKCNo& zE^+B3t)XezBHpD-OL`mv22VGgi{X@H^11>cJ%>T^;wVoPutE= z*L^MvKP%wbC-c{SzJDOLJk~C7@LZiw#Xe0h;irx!CbXR44ZhCVOJjq+DT&wKJjA`P zbFSLJugJCH$Y+JVD)$)gpJ9B-wZ4t|IX9n{wSE<7{nj258^{$9 zvNDfn!JlK54}Ddi-K}ej<+9hABeHDXNY3{1-pvu>2A!OZ=ge&8?Z`a$wZ#8vLz*_sn>8{c2zQ5ig{?>zQygXEn}X&P8! z{uM#CarVD|t$5bzf0^92^5K^U^SWiqk0zFx?a#40SfyHI75A5qrk3SoQLx7-Y5Dl& z5Z4FhK^F>5wA@{2lv4-PH@n+~J$SrbH~HQ?w<9*1%5JNlZP+TX##Hvxj@^BlWv^>e zMWQRa(zxbdFWek{+|}`5Fm?V$%fzP?sk;{A4Jc4fT9vbhCyp~YC%xI3=T~cd@{T-% zH#PQTW4?;5w&yl`)U#|tSJ zt97e(Ve0dub_!5Sqeebf*<4Ht>r82qS|pS2@vz_M)N_(XRMeR}2l&=X2z8}*b9Xe+C zD(yw>pqOi2`t>|pzjyqaJ2*I0*DmCf|)82sIzEyCW& zvrLS~X|rJ>UtFu)i`D~AUGf$^pbezF*GjRP8~^jcmMeuwj&Dus^u_dBg(n*4zq|7% zHf+PD(Du;4&(`A#F9Iw74((H|+lnuF#~$V%Bw!$2vH$WO$I$LxsYT(wThhbcE#0Pm z3L8yL;dD;t{E(d5zB^U&?EaFxIiK!`@(n4gzFc*A?1^Dk8k{-r4X;d$;arbmm3%BC zStdNsbUYdvdVPP+;QYF;T()aV*Dyc(1Y`g4Ji#|>iiPQGcs?A1?3LOIa*P=$ds}TQm;U5+4c|TE83@tSNG&*pl^m=R_$W-+xt4 zq*!TT?CF_EH(%pD;J>h`#J%_A4eGSa$)D~0~DuqMEjB0+jXbEDv7>aaUS zkRHRD3NK1M8K+1eiU*l`;755trj7*t%UcsdktPjyg;JK$Ya$y)F(B2}Zlc7IhC8Du zBJ=>(e2k$~^N=t6%8L`uKrFZLA)nTroBbF{nxT7lwEno zu`D@w?LoJ*&SHB#f`#TCa+|CydXuA}(GwjrctSh0@ALDR&}o+X?}uefl!~7eKY8-# z?}_b3F)=NTXZOxeE$F!#6S!+(%;=}7zmGoCuvn4$d)>)bb)0-nGuBx+$*Z0`nLX#W zVdlZu_;t40Tpu!M?uOK+^jJINn;IwA?1^@|UB19*PtCgE1qUw6Nq#w$ck80cNiVKA zNu&IE8g1P?ihIPl*(H_sEm)T{zcEGBn)|(Ft=yo3mR+p(Z7QFpPb_2@%Z;5j^ne`&$}V2&W4D2^Txx%g$F z`Pv)jHx?N1C;3L7-{5{ZljgI-wyaED-9tXK{I-YKR#)wzhjT4UE|}dFI;?j|?6}D> ziHVku<%OQS9v*C&^BndScW8JUPqvoic7>-{hFVnGhfL;-jEQT9iSysxzjrK3`qP->pnP9CTw#u6K`_$SK$R8wFz8mg*d08Qt1;F7HzVZt0`44jP2Aa3l+~e<*bnkc=$|JDB{dN)0HoyIerr*_Lc{kbD zp6i$Xv|32?%|5wFwm6B;cCqVkanj~GkL{6@-Qb+C&mtu)_4C1y+=nY3X{hUk7q1)> zHg(fU@MWKjGQX|N(=>J_QC`ZYySM+H*M=*(^W#hVx5VFSmls*Ze?EKFU|`zWvVMDq zg<&C=4__Gm^>}*AMv_(#On4;yHeG%(jYfd;7+XT^S zZ!P>)EW>T4Iw9FLH$}FpUUIzm@3qM*t8>d!^dz6{)zwz<=Fl8Gs8{GR&U)VhIXyT# zSib0KebVriW4=9+S__pz&fLyA{bMxX(ckKcuGLj>x3)-?d=_-8y=V8m zqUSI9uRZVlbTV$sd%k@?Ui!ISC_YlZ#VX?gZR97dsQu)p^z@yR&z>~tE!ez4V06^} zsg^^>v0n$MA1N!$>-0S?jfO7|u}-_Nvwb?wuA{Bt-TSM{sy#niJ}W(Hdo1XI zge<@Q?IR2LZQ2f8kPfZ?f?F@`s28HF(um$+9=+;_Xi{#+X$_UG%ovwd=~th0mK5~v ztT}$Fon|SkeSN4%)nQuCS$-)epBA})QYvia65`E&>~QYwoRbTd7K>?FDxLW;=iq|p#vzuHBL-gYQ}>RV z?;Ubtdz|bRt+=$mMmU}lpKUIybT2g|^>y;eK9#7HAlli;EXDqct#_x)n+skHX()=M zzg&7UG4qNcHCRHW$8Gsm#kh)JpU(c4Y838!FH-n{(@OQO)>rZ8mM3>yO?15Tc9%lY zUCXhqv(sDwa;B@2Tq~W_o^89Wyus>at&3SocGk*}0`<&XF}caKjaqA72Km^|6WSYg zrvE^F<&{L6wjtWM>x+-BMHejXva91ZvA@_<>lCx9MMhB>>u|d)Bz+=!f3~TU`k?E5 zJD%VedSn1Aag(VkVB2JftiyKEwxjm@A>s?S$ zUhZ{%c#G|XOqQ@jsPvnX8;L{uwzr14IIN^ux9$oY{uBN5)4o6(spIb55bXpqAf(-VK>a8r81L>~8`Cko|pA9~`iJnl_T zcq`!R=!u&O_*!}bSHxG)6Jd(@QhMT|B2Hg9(X=AI>Ys>;BIn`CbW}JGUr$f`nTH3^ z6aMpYKYF5dJ|09*=qce|^hB-_?oUtrR+`D>r99)p4Q1SwE`q91k+uphMn~2vxB)$} zTLoW2Pux_&>3av{n+S?>sxuW|sfw?r%g?IL7^0}nRMS@tkD`k@)$mAqqQnfc`l-*D zUSSWYRvkB|%O=(FKzhPo1K&bVJlDWu>50{vGfbN%zMan4YT;@BeNKdYv~h9tSql%Q z3q7>)BzmG>8&9Jr!gOYsum2LUx-+)F>EdB@oec}{jr7E$1v3q&v2cbdSUBT9pB^4g z*U@nU*O4A>Oh?c3@DO@psXo4yp17tz(**Mt;Tz~o+M<~z7+ZvIqB9!|W*V;50FR+F zR)#b6ykWt)0wLq zpg>%t7MMXS(>%d1IXZIUK4phVlhpGlb6Xc#x0@E=D)EZ)#;h5)^C% zpL*HNGAA?0oFg}KPz>$1oH1E!0w%fMF)0Y4bOS0M-Q@gn{U4X0K4;;+f3}C3pZ?`Q zE~fZgdUV1}!Ib{!KSA!!QC=jpc&40oLU{WdAw+^^xE$TSM_^>vR@m)Vnxa7OQ(^n!`MI@w5;XsS6W*o4a9@OiB=D*GR|Lw8;KYej@ z1oY{q&RIbLr`4HEeYL_R=^}w;AX>D55NRWiWjN2w8LyY%6X?95;Qw_RWNr<@PP)(- z6cWjoXPVJ)CyAFR=U z9j<`PmP2oIu*2zxW3<)|L^?JM5jWbuoFayPJ5&Efffza1M>|48pI%4FFX*w1)+9z+y# zM6t)!5J!OWMy~b0@#O4 zRJRH@!o;)CfGa*13Aut1J35$8sHtP=bfAo`5R!*<;Ev7RPpGRPxnP_Jg|7xlAe~W0 z4Xbfota1iquf;gg23K4PnYck=zh~(BV4!!nK`yIo!j3X3$%TuXPB&Zy%a~!bi!pYj zz6Nxj(wVua{SxHbMlga0h)UX^^n)<1Xrpi-slc4oXsOF&qw=AQw_%ckth{1@W8*9PxlXDD)A5lGUJ8Y_gi8~xTXKT|gi)&(u7mZ}Gnvrx#tpIQ+e}QMHxw+^OfbqQ zvX!zJnXUtOH{D|}GU&oOuw(rM4XnerVjG^4654v)28(<~g3s%r($sDe9DPmULm@u6 zK4#g+V5CvqOPmjl`QS2GQ$K^|Lt1ZOxH|emnLZ;VUE&LtwLg(y%6`yB*ME@oMnBvbTQ)@iE#xSO387jF#*bt+f+DLwD7Nq*;T=%f zF=0#sdHX|5Kk_mdY2;yt@uCrb@aLcaNt*}YL70m$3EBg22kg5j37jP`RTL2jx{Z<8>huHYKGcor)F#%*A0mib{GH6az z7=fE&f?iC_et#Isf}0@P`RiuWd?;%ZbYl(Q*|a2T4+keCBEboBzu7WAbRiJT{kjg# zusaeuu3rGD0Mm>fnv4W@^n)3U2HGA41!#pb7%Cbi7^85Kxv&`*L~fgb(T-p+*4TCi9{6dMhm>C%|! z_Gp-a3b@qV0%|06Wy1LNuq|WkY6rkHZ6kGw!v(3AnpI@B7*MCm`w{Kr)-P^ z)tdk7!SXTSDt9)MR(l@w09r0+(d&|*H>=Zb%9*XIfTm)=tM><)Xxl@WFi}|{6cY>9 z#}JdOJ{D^Hq>x}VkV+iP3Hy(bV5|hjy-^(Gx*7+$YBeZf7w&?E z)1S)7XAjIn95k?Z{Xd2W2{vL}D3qXuYKaWWNQhYW9ukaSE&5Hv7h-#Bk@jv_$}iWF zh3EuQxlsCU&={Lxb_WWwp(g~Ra+TES-zUh8m~jWia1Lx>NpN(5tTW|*4|Lfq&mp>uGC>F*HYMWY1s zWQLKu3Ejgr5yz2t5)?S+I%!PsjSxH9mjsF{W*E5~D(n#mX5V#0*@G{_s;-lVkj>K#JO$A zcONc^UZ%ic3cF7NpC`~ZTaM#%(Bdbv`iMw7LqQB>r-I{>&qyYy2iCgs3}U5SOl3#k zQgKPFSA5g_&*3EK8T7wY;*0+}?}c$kfnpgj#%pY3TdmP)=b7$fY^ z4+7xm{RAe6rYfPsECYxo{~~Bl${6z5htJEiW#vbs`@p*cEGQuZmqSMB5Zhr+5}5O{ zilDH1$a^^*$0@q-KK$HNkSOrd!KQlnXNtOUO5>#g8M$VZq zuo@H@j1W4P38h-7kxaHGs}Q_LDmR3l3UK(DTrk7pnl-tmb>6K@tx@es@^l2-)oe5D!OK znFt`211n!0Yc`6N#>I}5d~1I z2enZ19zuM(fG|cyLitd0&SC=KC@>#FE`5pwVP#O?zvcgomS33FZhOv=TKov6Y&)0> ziTpR}p%$SC>K9SRV1&>;1it=kBpHE2(4Y94NZ@k_c2HKWB)EA9YCQdb1Wu2kXV!lN zcb61^yYC+}XbxoD$tsA1N{IoM0s+k@6oQ_S3ik`3J|~}(;M+^+HLrxJLg>T5Ebni> zA{F8ap{e)>N#OO4RT6zF1YZ@0NoGM27<)QOg1tpB0!P1+psxs4v$x|UFgOe`SoD_! zw4*pzUM3rC8V`e|r>w~3I7EhE(dc0?SIo;`xRK)#C|_KhiK#pSI(2iI7{Ou)n5Fz| zh66hfBKLBKLH)$KmZBiPe8=wLI@y*I#1vh*#0mAP*L9|wmGCD zYfpm7kVulwJ_!dNu4o2eN8T}Pyy)r&@VIq58}qz#B8Jpjd9qVCEw4+#tvMMCZ9X*rG&G|| zJ`=OIfQ=u8H~b6EvD1)6qL@_ZJ`Hh*I?ezh$gT_~k`1LKQ&_AR$@ zq0BE3K#+LYy?<~X~GqD1zgK&Ux4A9&CdYbDE|UXX`#XdLq*rc*r89~0w;MT*_pf4 z8*wCGiThyTRN^U(N-81OPk9oIRl;yRtW1JYH84^6`d?IoFG5s@HIRG_%oNiX!E(h# zs8ya0gR#NH^cjF3MH;dTAzBrL&uuY-=0*>zpf>I%OiZOY`&=~r9xQrZf--6?nPfsX z?A*v86=atPS+5O~OwS%1^p=8&Q}i;(JnfleD=$L;xmPeT7cavI&U9sB_^&{1t=*ZJ zVo!EHvT0MUfW`TKOtPJU>>{X_F-xd!oE26qh*YIj!)=u3Mo?|w0mrsS&eB>H&d{>L zjG{=;R}BFfjwXN?r3A^c15>VZJi*DL-AU|R=p2ompV&antey(B;Gf2BhJqN< zy82J{Gi6qx?Mb9oT`f#hF{vbI+s6)j(W}rn8tF4evY>$f>X&~N3dqVLWH@?x0GhIw z(4Lb+G78rqb_?@KuXI$*h!L0e(fXGvgI2lKr}1qre*f`{r#5Z23eV3endq(9a{tOTwS{azCF*R!)B zpE__?{RecKtM#)&kyFRe5XjRyjHZFvG6O7ah>3YI3?AL+1ed!A?S~&p8Q(2vo1sw>1mA*CnS3Kb z`Z&>{3n0VbEy!^FCrNWpvda=ZLkQX22D<1ENyp!Y3G*ro@@;}BJ9BXeAaOPhL1Hn1 z7;$khPcd+7`cDfdgLq9~mO?HsLqQ0gZiIR7H9yJd2y;l2OQzx-C_GS@p~!`N?m++L z6=yJ<$Y(AGl^m`^gmxy*B%61aSg@rT3>;4G!i)(s9r%W$M|WX<_^iPI97w$h{K(WL z7!OQUpLoh6^Jdr)r5bYZlWlEeF{>V;rVK4p%+HblGN`y2x59!Q7=RxM-h-BvTuCs} zD0DT42)VMUuA5~H^CT7O?}2B@J|vji0xN8-KON+^;oK;(1-#S@{zvemj8Jgya|?8> z&W-=E%UWT0-re$#5I|>JAsm~w{UfZgIvSCtBEBRJF|u-Msk8iH-9sweY=ee(-Ae-e zK8(lk3N&u^%Ry)T01QKH7z9QZ-?s{*agrfrB67d(E7)q`{^mkm~?Z< zk!KIP=d&WA&_yZ;cEIQneNKYV4!APuf5`yc$Y_8=mdxM%W>)@-1EkjSClJX;gCvl9 z55Ce*I;~HjlGJwuEserIaLk`M01eMFQZ>X-fSu7N4!93zO!$GLvsBH72~|Jr+o@E&G%k`BLZN)K@>y|{3g@~Y zR^@^OkVVrXoH(&T7eb4=iH;`Dpt;fZZs<9xILSQfhUT7w(4Qpgaja%;OYB zJrm$!C>oOQ2 zguj5kBWu85I8f*d(9t(1nKVmIabh`D!zL|BW`zyZxj7$dv8)%0*Jz&&SDSIQOq@_Grm-CRlL>>98KZ${LxSa*`S@5u@Ge#CO9_6qFjdXaR%D~R0J z^(3(NgEEaYKxdH9IqXN$V}YC!WY%SUKpO@j-#*+IlL;logMBblx^6;I12CT%_rtLB ziy}crKUDEYGzs4KL+HD=lVHgJfbF{ouo63zNEpIV-vCTsuTmI*8(F`GdB7lpWC~ux z+H@qF1fOy_rO0(hVGw*8%4N{p$Q*GBqR2t0{9Q!QlIY4H+*}?$Oakf~=$7^+Bq%t+ zDa5o<%6S9E3Qm%;<~LBW*mEsce{VIQd_H3)H_p8%9TK=FUy zkhJFqd@aUX{2>P|BlHdH+fCyVo}=)h-UOGh|1&A|nG zKOyMIlKfoE6U|p{Qp=p5OAJMR0!uwY3`PJoeu8dUCq^$5%vGo3(HeU=lL%4~fT?1nmn5hmtd zHH=l8V6>3?XNc1E1q2Adwl5;d$R=oZ`t_*&7OD1}!H5a_x z`vR7?E+^^QZxAi|WL)by%e@0Ggn|sZ{{?~(zM2GbU-1=~(OMMs6^`RJn`7v0a9FvNTVuciV>85D1T*@vSq-{6?~J(4VC<98r~qX__O z`gfS(w#FjL57-&V$D><6;8T{}KVZIkLLY+n-bltX94cpdfMgDj!_XZp zBmi7toaEv_6XV2%K?#F_Ex!`%=;;9n_z8~LokR&g!I$YW;;D$Hf5Ofz=^Wt;j@D1W z+{0T*g1QOVkeF8yKoXhX;}S%gzo1V@Uu9yp*Kxr{{uj8^S;s_w{RNx5Ee%Xedm{v~ z{W$cpO~1j5uXh+SMRK#+MbM~~r1>Uc$ufP2TqbdE?BWyRDTVG&!cJqfn*ca6=>>m= zi8*}PAINCki+umU9MbcOcv6w-YY;n>KyhCQ@oKoLAabevg&D(qhy=U;f|DE{8Gr+M zj&MQ0B<|yX{e@i5zmnc)P2o;h*iRB%`wcqe%Xs1jGkt1Sm++q?wMM2OcJ?et7^A}G zmz7%p#c6}DcR0D3hv^YEQeljfTadV7hc7(12}T{A;p4{himAeRCR9mmDZEJsGB1g` z3`>T0=Y+zp4;-9%f2cZ`uLMbi%W;dLlE=^m`X`|RdUCT$;+JM%|7OM{ zRxp#YkfC6L?KB{P92?aXJGO)bKTW~*em1HaMlmCqUN-6?jA~5+eRirImTX4=DoSCe z8etcm2!Q9Wgi4RGLq749bOJ5nfP7W(Isl|-F9+mX2`>Q%pv6h$K~F`fbC8(QsE^hxbY!~1css9!enoZjhLnF08cg7lXc zWn2)ESCNRq4|OStJTwuw0D}xau?uUfXI&M%r6i3pZx#4xxNIV!Rt zssXnD5dj=9^q6=`p*BIPKGxnv0vRFDP=e`#P~X}IM&U9T7DplQCIDs+f^HU~8e^jH zs*eD&!cbM7_as>R5jq@H72XkuL5ma$!|=QgZ~h3yN5a&_SkZR|;6|DvR9!6o56MKb z^01*t)7%`$E)}K%TUH+CsX!jCHRpm6&=Nw=MWD5wv676OD45ORWQf^NoG8?1CodDz zF2Ey7r?)ENX8d1UULk1+A~!NZ=qvT|)6hx>6uGvlHAo zL#$7Y05R?a^hE~fUs6!(m^~zDN`!!m0$%EYXn4>IWJnY|K$VHthi5@6XU9fB}61?K&l_ai^ zW?E^R;H)ew_(-iIf^h9ezih2jhK3juB56}GUQzOJE2aW;xEM)amjK#J1sd`syrCqD zY?I~XL4T;cyyWJ;iO}9DMam{sAZnU&B-o({ir%V_RewIoB&k51==-D=Rme4|M$%KN z&~pxHGXOXGynvSvMXEto9u|R113K-(UjZs9qZ;g!S66OYjWi6(l!o^R%IUHDR+Atgsi648|0b z-O2#$NJaOa9JO+-ToSs4Irc$}n@4Zwx7X9%zujTyj_6j@GyaLOyBV+h+?(<(j=vhXw2 ze9Xfy@e-jo7d@)xlR_U&!SMX6vlOPTFciel`m11O|6*|VDBN@q`OI(e@t~KBA!6Td zFc@L9*a&o@8W;=@y4T1jjOw4mgk5F?o-c>n5JvuYMlc6Gy2HdM-QyD^F1mz}-xAOk zhf5NMc32x&qF-YFpzYaWP(A?;*F@){|3mUM5 z+UN-Ib0af0eoiE70*W+NCOXUn7C$FWCZ^Q{Ht>Ty3`Pc-n?f#s0S3c`GEBj|oeIfl znNj&s-g;QY=_icerckw5HHOR-^U`1depIc^FGOApZqwywZnG6y3@tts69C_F)6H?4 zgSi+BQf6WfA+@k2L6$vO%JzlEy-4Wr!Jm&1wFR07eKv=!RH!4#2nIpb>z(;|k+TKV zWTP_^eRCB*2Qu>bHz$7xoaNJPKZdFdxjm%&B)SyJ>keSZc#%#Bm~meU)7~>KSX=~yF~&~Dkl=(ROdNgj1aPNxqkc=O3ff==HTaZ3a7w7& z3gUfvANpcNT?2ogGG;}EuhN&nCZHR31y-QYz6>@br3Xl`*c#?*1lt2E7+c$3z@1#J zH8>n{nlLsO?LH6TxN(+Wl&MA@=V#S>;aP?%Kl)_`Ar7(u3#K z^KByo@E{jk@Yc79WGY&qIo3FVi7U2X;z&DsY)jpMbv!1Xsz|33#KCq{HOf)cP7rl= zklFDW`m!A2R@B4KkBZhqX8qn-4#LYsx`J0PKNs1XqLzbo>HtCOqMPs^rtq2oA=t4u z#8U@l*n{Ox*a0kuqi>%*^z!vz2q1~he}`b)_xd+Cc{+fp)Cto6{SL5k?)gK4J_iW1 z)ieXZ2V$52{k71{n!blkfVoe5!;68H5OT=JjY=G$^SZGz7%ue35j+~_Bbg#6*poO3 z32+eK?!q}F0G5IvC-5XtfT3W4>4}nH+zBROF);#Ak@E`ZKiqQ}fEQg}0ggJsi-H+3 zFOqhK48BrKOr5L%KicmMefFXZ6V0a}Ac=IGA?7?TQ2Ii6r@%0hHBSKEf)cV&x=eu~ z<3ZPYxN?4RXEf(NG{Hvhw4~B$P5*Zjn zxuFCzZbUMbt6;#S+mhh#D%di-hwA}1Dy*C<1vt?rSJ2IcujmP;-W9}4;j(}LMXRA^ z^lodj8mgcT*9HWgx*B@L5PWG*fL8?A<4FKdN(&NlgRzq1Ms>neHjoM&Yp8aZkw0=- zLtTY&#i3*Fu=d?q1G!Y;M69G^2fkkRZ$hhFs$*60~~2M8O4L z=z3DUFatPmdr}opRz38iLpU@P@`MQ7y-5UdE^70HIb-k^33ToXaHHVeptHyebXs6F zB6K!-!A{2>?(7M0-3w;1J#c4F03mP4o!UWyr=8I8=_Mq3L+<~zaqU4-RbiYKc`k78 zDk8WWDuk)TfcOkF!%1UkR7#uFQCJa?U2%E%K;9rA@(9;Qe5oneANfqFMl*b&WBF)& zFeXVTNn%Dmf*i-jChK?h>|V}w`fKO=o$qnZcfNbRyXTzmZg1sqaR&zWxXnjL{&S#N zdsF3xt{V!M7qr}}FcW{P`PQ=L8?T*#@aRMwy-ByIP6qyLm z#QmZmo=8matN9^E@EIc)I^N^sP7e}c_e<>kvw;B~r&;=h6GcWmriZby&sspZQ@ar= zu0I!$utk`SKb&cp89bBRq=76Cjnee?<4A^=D5GuNbVdVH_lIO-+WT z_W~5eo{XzUs6>)OIK$m!1jFnRoM;G@yvU5wJD!>MgsVhKa9fJG16;0Dvjn~SJc1*( zi}AOYU`5yysUXueHDftpO~IS8aXcq_QZVYqiJUN|B7_o`;wcM>7LX=}G~!YfGiT%R zj*;BRkP7bwy{W)4njfYrgiPP3LTctT0ofl5pGTV@H3v7X?8+o+jKcs>VvcPT6XMH+ zn^tB$PDV|5_qs8Y5lb{f<2kt7jMrxGg`D`?jDZvyIdN$j{&1u%gUoM>6eLzN2Dhx3 zwu%(V_R4Et=ohEKQhqWGOUM73`ZT2187T_kPPo7}T5~#8LELD;azxjp)dKQyj-;cl z1xRAH)X};e8ehv17y>Mq`AFQ4Vm2}?*ho85#)%FKvc+axmP*GGvaFK*hSI)t*c^xZ zQtA3p6dQ#1F`M3(GoW{#mBGQZAOp)o6mCf|;y5F`ws69bi7|}W#)x55xC33AwE`a9 znhEKTK4I`s`n_I~nE$acc0d(MU+v`#5n1qV?g36*IVAPxN_J;KNeAvpF(r4hV5t5u zCo)c;;Nq{Nk~d=E%6DWT0}6%udsX#rWk3hx!hZw17AH4^WTa|#m9CJC42T2v-yUsf1A>0pb5%}RE7 zJ|G(=qgsTv_p@Q(*fjw;mW_e!ye=StYru2qM;2-RWUC|zY?u7Vx&}U(*e1a3w@{9< z=_b|<+ukRC;m(1{s-M(c62<30*u6u5r`(s^sUZhb^yr=%4j|85aQi=1!&+LHi>Sq= zPTe|3#|pjV0d$ga$7==HH4lsM4Q~NS$ipsM55?pm8GfCIwd7)dp;epD_bB1=A& z=wLqu8A9#(uwucniru(O;RTq!dVdA+q0I&8;J-LjvGcf5R{``C<2*&_^7ukn_dr>q z1F0**LswUb2P!N?g-+6}dbJOr`9o2yIu7$`BoB*jsI@cmnER$b^Czm3_#Nu>F z&0YK!>YsL%!uPMl{7;)VY0F^z`Bb58)^voD&26j8FqY_PLfgSI_VB;WkU+A;fzeP7 z`71bkvLm=+G(-01=PcXGAzzEKO?#V`elAB`c;G#9oqn#yfP*F0l5UiJ*rvZdA8t=l zP1edp&UG#cbvr%lV9f=EluRzF0!!9}6i!r`_7!g306S5}_sl*@e+HWuuR~h3IRGo=!IN3+ZmmR@fJhu1JP>H=G4-|MY z_*64uqPr3)D)WSbgpjEU%6gkQGUcqSrwa_}ca|akgo?6(6jTj=l%Oy~K}xDIsLfXt zB$xshI&#tZYbwv|y2`mwi6+rM*Pt%31_s_}72s`cvM-sk9U59|;G2gxIfJcKP5Kaf zj4>!0VLbriN?SVR;mniv1lWB?mhs&VN4f7A>aBqneY?23?M&{q&^r&+CUz|@wEtIm zsGud2F&yp^7~~DGaHJOTbo#CuMzKb>fNXexDYWfsRXz;Cs^o>}pu0LbMNTN-8`v%E_jrzgPX~EjzA&H%>|r39D*QK7GSK$ VU;u)X{W+{BCkV4_<`FVt1pwdV5h4Hp delta 76 zcmdm|w@+`wG-ggy24@Br22%#h$rqWdH{W6oVdb=BaAmM!Fk)~83R!M0;Pl}TG+;1e cFkrA?Fk#RG(m*)bpTl}`f-uWw9w8%E0Ox8EJ^%m! From f51cd621d27ea4765f6acaf42d526c94132c4e78 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Fri, 13 Feb 2015 01:35:43 +0200 Subject: [PATCH 10/29] Added game piece switch in roller gripper --- src/org/usfirst/frc/team3316/robot/humanIO/SDB.java | 4 ++-- .../usfirst/frc/team3316/robot/subsystems/RollerGripper.java | 2 -- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java index b2b88f9..0747b62 100644 --- a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java +++ b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java @@ -48,10 +48,10 @@ public void run () put ("Game Piece Switch", Robot.rollerGripper.getSwitchGP()); put ("Distance Left", Robot.chassis.getDistanceLeft()); - put ("Speed Left", Robot.chassis.getSpeedLeft()); - put ("Distance Right", Robot.chassis.getDistanceRight()); put ("Distance Center", Robot.chassis.getDistanceCenter()); + + put ("Speed Left", Robot.chassis.getSpeedLeft()); } private void put (String name, double d) diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java b/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java index 0d3b765..9e30569 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java @@ -4,14 +4,12 @@ import org.usfirst.frc.team3316.robot.config.Config; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; import org.usfirst.frc.team3316.robot.logger.DBugLogger; -import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.rollerGripper.commands.Roll; import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollJoystick; import edu.wpi.first.wpilibj.AnalogInput; import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.SpeedController; -import edu.wpi.first.wpilibj.VictorSP; import edu.wpi.first.wpilibj.command.Subsystem; /** From f737098b75e53bd99e3977f039875c0184fed5fb Mon Sep 17 00:00:00 2001 From: frc3316 Date: Mon, 16 Feb 2015 14:37:24 +0200 Subject: [PATCH 11/29] Speed for encoder testing --- src/org/usfirst/frc/team3316/robot/humanIO/SDB.java | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java index 0747b62..fb703fb 100644 --- a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java +++ b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java @@ -52,6 +52,8 @@ public void run () put ("Distance Center", Robot.chassis.getDistanceCenter()); put ("Speed Left", Robot.chassis.getSpeedLeft()); + put ("Speed Right", Robot.chassis.getSpeedRight()); + put ("Speed Center", Robot.chassis.getSpeedCenter()); } private void put (String name, double d) From 18185187c14874d4278ef89081258fe1804a209e Mon Sep 17 00:00:00 2001 From: frc3316 Date: Mon, 16 Feb 2015 14:58:18 +0200 Subject: [PATCH 12/29] Added code for integrator testing --- .../chassis/commands/StartIntegrator.java | 40 +++++++++++++++++++ .../frc/team3316/robot/humanIO/SDB.java | 16 +++++++- .../team3316/robot/subsystems/Chassis.java | 11 +++++ 3 files changed, 66 insertions(+), 1 deletion(-) create mode 100644 src/org/usfirst/frc/team3316/robot/chassis/commands/StartIntegrator.java diff --git a/src/org/usfirst/frc/team3316/robot/chassis/commands/StartIntegrator.java b/src/org/usfirst/frc/team3316/robot/chassis/commands/StartIntegrator.java new file mode 100644 index 0000000..9aac29a --- /dev/null +++ b/src/org/usfirst/frc/team3316/robot/chassis/commands/StartIntegrator.java @@ -0,0 +1,40 @@ +package org.usfirst.frc.team3316.robot.chassis.commands; + +import org.usfirst.frc.team3316.robot.Robot; + +import edu.wpi.first.wpilibj.command.Command; + +/** + * + */ +public class StartIntegrator extends Command { + + public StartIntegrator() { + // Use requires() here to declare subsystem dependencies + // eg. requires(chassis); + } + + // Called just before this Command runs the first time + protected void initialize() + { + Robot.chassis.addNavigationIntegrator(Robot.chassis.navigationIntegrator); + } + + // Called repeatedly when this Command is scheduled to run + protected void execute() { + } + + // Make this return true when this Command no longer needs to run execute() + protected boolean isFinished() { + return true; + } + + // Called once after isFinished returns true + protected void end() { + } + + // Called when another command which requires one or more of the same + // subsystems is scheduled to run + protected void interrupted() { + } +} diff --git a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java index fb703fb..7f46a9a 100644 --- a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java +++ b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java @@ -10,6 +10,7 @@ import org.usfirst.frc.team3316.robot.Robot; import org.usfirst.frc.team3316.robot.chassis.commands.StrafeDrive; +import org.usfirst.frc.team3316.robot.chassis.commands.StartIntegrator; import org.usfirst.frc.team3316.robot.chassis.commands.TankDrive; import org.usfirst.frc.team3316.robot.chassis.heading.SetHeadingPreset; import org.usfirst.frc.team3316.robot.chassis.heading.SetHeadingSDB; @@ -41,6 +42,7 @@ public void run () put ("Current GP distance", Robot.rollerGripper.getGPIRDistance()); put ("Angular Velocity", Robot.chassis.getAngularVelocity()); + put ("Angular Velocity Encoders", Robot.chassis.getAngularVelocityEncoders()); put ("Left Ratchet", Robot.stacker.getSwitchLeft()); put ("Right Ratchet", Robot.stacker.getSwitchRight()); @@ -54,6 +56,14 @@ public void run () put ("Speed Left", Robot.chassis.getSpeedLeft()); put ("Speed Right", Robot.chassis.getSpeedRight()); put ("Speed Center", Robot.chassis.getSpeedCenter()); + + /* + * Integrator testing + * should be removed + */ + put ("Integrator X", Robot.chassis.navigationIntegrator.getX()); + put ("Integrator Y", Robot.chassis.navigationIntegrator.getY()); + put ("Integrator Heading", Robot.chassis.navigationIntegrator.getHeading()); } private void put (String name, double d) @@ -149,10 +159,14 @@ public Set > > getVariablesInSDB () private void initSDB () { SmartDashboard.putData(new UpdateVariablesInConfig()); // NEVER REMOVE THIS COMMAND - + SmartDashboard.putData(new TankDrive()); SmartDashboard.putData(new StrafeDrive()); SmartDashboard.putData(new RobotOrientedDrive()); + SmartDashboard.putData(new StartIntegrator()); //For integrator testing, should be removed + + SmartDashboard.putData(new TankDrive()); //should be removed + SmartDashboard.putData(new RobotOrientedDrive()); //should be removed /* * Set Heading SDB diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/Chassis.java b/src/org/usfirst/frc/team3316/robot/subsystems/Chassis.java index 5efce34..dac1182 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/Chassis.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/Chassis.java @@ -23,6 +23,7 @@ import edu.wpi.first.wpilibj.VictorSP; import edu.wpi.first.wpilibj.command.Subsystem; import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import edu.wpi.first.wpilibj.tables.ITable; public class Chassis extends Subsystem @@ -104,6 +105,9 @@ public void run() double vS, vF; //speeds relative to the robot (forward and sideways) vS = encoderCenter.getRate(); vF = (encoderLeft.getRate() + encoderRight.getRate()) / 2; + //Added for testing + SmartDashboard.putNumber("vS", vS); + SmartDashboard.putNumber("vF", vF); /* * Calculates dTheta @@ -139,11 +143,16 @@ public void run() double headingRad = Math.toRadians(integrator.getHeading()); vX = (vF * Math.sin(headingRad)) + (vS * Math.sin(headingRad + (0.5 * Math.PI))); vY = (vF * Math.cos(headingRad)) + (vS * Math.cos(headingRad + (0.5 * Math.PI))); + SmartDashboard.putNumber("vX", vX); + SmartDashboard.putNumber("vY", vY); double dX, dY; dX = vX * dT; dY = vY * dT; + SmartDashboard.putNumber("dX", dX); + SmartDashboard.putNumber("dY", dY); + integrator.add(dX, dY, dTheta); } @@ -170,6 +179,8 @@ public boolean removeIntegrator (NavigationIntegrator integrator) private NavigationTask navigationTask; + public NavigationIntegrator navigationIntegrator; + private SpeedController left1, left2; private SpeedController right1, right2; private SpeedController center1, center2; From b86daffafc027fef62a3afc226d2d6c57b1a55ae Mon Sep 17 00:00:00 2001 From: frc3316 Date: Mon, 16 Feb 2015 15:26:09 +0200 Subject: [PATCH 13/29] Tried unsuccessfully to solve updates sdb task not updating anything --- dist/FRCUserProgram.jar | Bin 1782453 -> 1783355 bytes src/org/usfirst/frc/team3316/robot/Robot.java | 8 +++++++- .../frc/team3316/robot/humanIO/SDB.java | 11 ++++++++++- .../team3316/robot/subsystems/Chassis.java | 5 ++++- sysProps.xml | Bin 5950 -> 5950 bytes 5 files changed, 21 insertions(+), 3 deletions(-) diff --git a/dist/FRCUserProgram.jar b/dist/FRCUserProgram.jar index 4c34f2c3bd92a409d301c7ce7d19d0fbfb72669c..90a8d36f80be2bf29a8b079598752f5b8c40a532 100644 GIT binary patch delta 32992 zcmZTv2RxPE|L59!k9)1`kv+?@G?<*g`!P5X zGShh5pUQ~(SCO`iopf!jq22^6_AruZMxR`VP3~tMW1iQf z@6gmoj*q=xzC*+pi%?sQ&Ce@Xdg@z$M;=gM*Ng1M8P~-$_@ot4acd-AX}wA`?t!YY z;1esWcBh_U^&XFIk$Of2{FiIeFO#kNG4c_CmWmbKEdtMSZt->gctC+eS-EyY&FKkp z?fv`Bi;-`=`Ni!nD85|Q0B8s=NeGV<@?s?vMieJeaODOoJsWHfOHY1ji_qI>?2*2i z=eS8ZOQh60Lpq~j74O9T=3-B#GBM`{>1Qb%y4eT^fHu%*oRD42E>y-Sf@9+cYb0gy z{aqYbXo+Q@F`MKxUxwl$d0;(_WVAOXa(7Y?uO|;XX75!SUz6Sy__}nTFcP1N0bkqo z$?MeXL4DWAml970{oK#$_YL`E-_(&-zmQNm@tyaSld{DKWVOxE!apC2dhWeykTtsq+Uh37@oeJy%PGIj!T zA|F;Lq5{7%Ju~Z-rImJhd5xE8Vetl%36tf1%+bCmlTV|P#hq=NNs$CN6Kk5GinM>_ z^A(f59bU-=Qazp*Cnok%wRgpQ{dZhUS)T1FQB$f%M>up!FDn*f0TcLaalh9lL1mg539R(G;l0Pvqe7|ciBiZ`J zpM{O6aOQ3vhZlL#Wn4FNLfGay3r7@5QDsD`IR(WijZ@>7dFrEnJd_QqRcdlvmPk?P z+vpHTer5BC*ds1Y1*5fB)EOthWf94fp%9#&v)%6M+pEF3!TS7iWX2-B*(SaD1NrJh z`d+F-lmz*T$^*sfNSmix!dg?oBFGOqp0O{;Y(gF{ikq=?9|y9`V9H+=R{E7r?@0BO zeS4ffdv|3Ob9jGc2UEV{awrv+l1uHjwTo|f26KLzW2Mrw>T4q3G|HD)FMXo^rq{uq z(bpUJkULQE;#ZQ_FWir#W+Fe9J}Yc(kHCtbdh;3Seoysd+HH;8DSbN^Uap8l?ffW9 zHw-?B#l+pIBOVf0^HY!QnYS5JR?Z}Iu7nou4Vw!*Lvcmg3(pH5mrPxM)jmCYyfB(z zLUL?K@|ugS<_z=C)e|+hFM?9AB>ZbhMUh%w2bZB5E6ev-5S6lChbW5GUKt_|_F52H zYrhYJXra@&v?jsL1ry>=+;3w;)Wuu)oPX*QcCN?j?{`ig2L_x|ir`8Z0VBA|MSr_< zB8c+1XHmlys&FoHyq9}U3BxD|NFkNBIj;0ym>3vm*r>!*0aVUC0;GYjwYTq84_|vn zZ)@M%-h#Gn);>OE29~Z=iqvu_j~a(&uDbfEQlr_TOJ&QtY^|o$1lV!8WX62Qm)>V` z86?k(irr8MMG3|7950d`sK*2((<|eL+W_;yj(eFtdoO|aH(w)vU?1SiV18~iZWAr1 zt9-zKnf^rHAi?)rHG~X$N|Uc6tA9zOui2vbBxp_bbi4C%l6>| z27Ir))4sD9+7(}CDC^Hy538zn4J;$ev);>MP%+T#N_Qc6KDK((QNEtnN0_yfe2+V3 zqKYN7rg zWu_g?SILt|`mk7KQ-t5$_)7Zdwbln^FO5odZp-px9I2q!HtP&6mshmn!fzm~`AE~R zDHoj{zMPAW4-u*qh1n@D%9az~Bg2(jZPBsqo20Pwh_-la<$c$Nz5n_6{To#Gq+Ax> zbGjYjc2p|LrRp7H{X4kv!AFA{ruZl4L$E2~2pW>8>SRr5WS%8II3HeNsb1&eqqJIR z>qfmuR{}}RLHhprPQCPG03WhqwHHC1)#B6t=Nj6ZC9zN^$Ka40!9ocga6$?-7YiBA z9|1I;wcwra-{PI?!(liW7}tqW;RKURm6@+?u=mFji(yziREcJu&p48F}vqEA#$cRBhqmQ^dn( z-1|TG?tc5V-Wt4cSM2AP?1fM~Pnl2x8>*wIk%;>j_7u(4xWW|~lSHVyUP;n-AX$l{ z`qt&)-)h$HlQVZIi;~vlL?o$RSIZjmg|o}j*-^jmyVbxh`mp-e08dpFXQxBH9-QpU zPM_zUBfFG4@?0yDZ@KNBuAWf96LFnG`NItYEqbVA6?j*8v!d)}nL5NIhdOIyW$D_! zV76Sy9leO~aE%Hl;hp6zwh!p?v_R@Gd3l#Ub1f_{A08^Tb#&JeNYl(novUzImXqnb z{mdHvL6E@ZhQPz^C=T(iofbiB#evGhU*5dWWx~v-IJ710KZ^Tk_zjRT{rP z+OodcB~tuSos;M4o3YHtB`?dbznOK#&-=>9H>3H=px()CWpPXWO;&iJdkOmtQbb!q z;(3mPY;Pr@%rcw5=EWF|3bV8eYnyc0^HTl8$%?O6cW^s9E@-~CCdiGq^!E;`XeUVG z9Z7Jj7!hevZg_|#sH&&Cy=H>FWJ_SAhxb%Tw(Gq8W=|#Be z@`j!dwauH#l-^G~?Mw2Qk?NEwS!ACQ$}UOVsq!`q?KL_OVc_At+Z9(JA!IVK`7(P^ zHmVjN%v#qdGM4YYLqJ58@~iJ&?#Dxo^+rWaLiv@5qCn1a{4c!6PhURaPIX2iO>S2D zw-;Pe3m#*_xmhip0-xkfY&|u3k-qQB*LpL~>8{b_rw1dPS9v5e9AzGb5w^AmV1`sI zMy0z(QUB;`IuN%koLr|4bR4?wTT0k;+03rVdLsybWb+Nvn)@WB zT2DZ!K)lx1tBMr3EOst5y_dA-uS)i8@Km@zXN^7dHHo!<_!o->zu}89zZ+ zP%=k5`R2j*Wpn$lu-wd%JS36lyVxINYwu-Cv`-nb6iPIRkIBmACjwm4i%J^#pB8<7 zk{Oil-1zfuMNz4#mvi}m(P?*@{~(W3mh}w-CY`NcW|Md8So){lKQ88Zbw);2$K<}5 zqrj9mUi$IP)+asXuQ3GaYDdvqY2wJ>#(<2?-*K@5h^YI{YPt5ev7&*A?@CIa)+RaxI?UAs&Bh{TU&z^!=tI&0@04@wOjS z_1{@DBn%Zl^P+iRnjk!NOXeyeMG}MmExPd)!JQ-CLPhcDx{ITpEA+6HByRF}WTdj~ zV+B&x#Uc^$MBDpq0v!&yZPxec2wF_1h0@!`oQ`qt0|YG=$K~Y5YSypyrx!R5hF}Y9 zo+^t*unOA1gtju+0^fo8{dW|t;q_iG=xl2F>WRFRjam}AHIpQj87c;J73^WAnr3EE z_NIx(wfR^Kl~fF)c&YOCGG31fk=FVY*LC674KRmw>xUnG!x@;zw%;cU5<82a|D_gU z9$8^1YSEibnVR=iPY&Va;dZ;3*pDwZiN~HLRg#yUEzcu?23JjFISqRz%u4UO2M3qg zcF5^bDljU7@?)twdfPvvu5)DeZMbJf3MHZaB3;UCU+r4u9@U4Rji`0uTrTayijM0U zI-|fz1O6|fzn62p+T{#W@Ia|XiSqghE$39o6D0K-{ESq}L6lg8KUe>XDYZ2frSTPV z4Px!;3%NwOZj!+x{d;y|c49S|>Du>ZrpzzuPE3K%9FsH3x^ZRt)ddBrwGFTKPg{|j z*|$#bI$r9HOy%Ip&ir;K8~l5EXW`@BwMk6?b1wF*csjP7kFmRoudC}L&qJb(#`pl_ z^I~dOkvZNKIlfZi;^kL?+40SWPBxUCr!;eA%UF%-J$Ocg-LD?}2w(KBhPB@;i#0e- ziXCs%!Ee6VjdffZo4BY5XECaxXQ8rC5L{uU(fmXJCwp!hsYAHRt`w$jFI%+iK+JcX zLeFAy5Kga9ws=(}RIT07KIFR7r#p&g$dq_7zNuTfJ!Ul9UB|VtUu{Cvy4@eVtr2a_ zu@M_4V13JboF}}dNtk7F@ZiB0!qyjy58_$jcL;or91NNqIc(f5n`XHcw=4NOo!@Sh zyEantiTO*rOHxktxN|cNy_73j2^wYQhJPh~g`97aV90wo?;bpQPZ;6)rf@}mx(hjf zb#_Z+oYGjQPUb><{V7(!a6irSx;uQhuU>}EZ*9bT_kLzW^}PtX5}@@;#}Z`iB4f?$<6hg6EVDGh?rw+G;euqSp4gH@IOeopHc8e(kb$+p(2v`E6$x ziu%h>(l+Zfc;Y5@QMw;Ip7nigYIKG-BfWplM~-vSU&HU-Ey#LrGE#Yu|67oD&}(a4 zW1_EeH4C27JjNXi)lxzS>pa_fv+O3bx&azW-S@KkPrk36+*8Oj zLK1_EOPl?znL$(BwiJDh8z!B?+wqr*NNz6_grqZ+JV_!U=yXl?iV>W3xkEZRBX{TJ zosN_TX{Wy9!%Vpa{K>sQ8Q0EJlz4r52S-Hlqzx)kPNR>0w33Ml;lDUUxt^+FO42-X z^-M=B@xeg)tx$3T_|3@!35&E5StCYduyf?5S}=*6J)ttm?O+Uj9};HD_~lE8k4K0S z&-Olz%y>Epi*`-QORXQI>6q`BDKpAQgfJ~6ebOdb=xDGHQSS`+6boKBoW@s0vMff4 zh88UK9>;`de8TVAdAeVjz3hkxeRxxNXC;m)&GA5M{6OkX88gaPK{Fj(?x$jwfr`v$qFZ$^WQ*-6pi$WvURA5^a&($l-aQ@cjP)HZTPm;QZI&Ar0S>Jk?<~Os}h&ER|YA}l*cRC zz1u!7uCDa+Fs`YXBkVMaZlJ)YI+}+^2!19gjoJIqlHkp=q&>%&a6dIZI;O#l(R)d{ zJv;K0ey8wX)NjWG|?+`90Gpt3kt!(c72 zOyXuPcjP+vVU<2%u)v61hVKW`!FuQVx6CO{UG4l|%<7+(y->21KFg%$^yw{~w`=@& z$SoKgyax`w-%PedRrq;HZ3PtUXi>SiwqRHTNyVQ2DV$~U7J`MUKm z>o8okMmwNFjtGq$dzUu!);Q* zNH31}&+UvFg|B^)<_JuE6ia8l>Oy9bz`I#=Ei=+gYq*D(@rJLMgm#_~tF`E><@cDe z+$O6oO1ZJF2RS)dv|4s@AKss|im7CB5i8iVUVaCRoJzz#FD_rFo>W*c6Or$~=lyG% z>ttWT|JsjX%DWE~s^wrZk}SwjB0l_@s^x~b#|Av?*ls1S@k@TmI*{bXE1!__ZK>9Vh$5D%9j4m7pbzaJSQKM;$-P3(NO~ z%H?cdUilT`+MKB8i&PVI+ND^GoQ#YHuH4!8ZQLnR9|tGpDJee=V6LM^N>-H8e)-ZE zYGEhgj`1+bl7*H{?Ecq0k*O9d*wolc0jRFCn+kk({!z@J_hSaowrRRg5C2M zE`zowp-Y(*b6UtU{IWrIC8YHuT_y#KGO`#m<`hdG+UMokGm>iNp&rjJaMBCNe0(Aq zE^9nK+d(mV9Eyj_YPCNp`4Fd(O7r-NN1LT-T=QsbuqWQ0{jtud$TN8A>G9bG!9`Z@ zJM?s)@U6ORTd{7?-{+H!YFOI!^^wSO&>|c6BRatT(4V@cZ=y>^(dWZ3WvqyGm@$vDY8lwEy-R=4f?ApzT!xLf;oS7SB z6=*+SkjZ*V?oyben6xg4{9t=sXdsdJA&)~d$Q|TDkfn(I zcI>l{Q_;7ECE2pZHhSXGap3VHyXUkzQ>T5;A>sAKH3E4_vx9d2)gSv9`6Ov7@Gop? zRyB`#pFQH(Z9brpOf@>g`|mLXy66~Th*RSQZ+r;}Flvlmg7op>ms4npX7 zO4osXemrIBB*cPv-kwq%NDVxu0&iE~_$boBb3Mf1D+sT7Kbn9G9b=uQuR@34n(5cj z;TPpQs}He#vwP=f;l>Z`=QMcf9S(#We(XNy8Mda+>DQe#h=TV;s*srdAoTodDE~|2 zISf_4Pk{O7AsK2;SORInOmv?#BcG%N88BX6s1f{P-o$amDa zF9)48VW(;oF!o(zpj`Iyaa4_4jD4=@2i+zY^#KOR6#l^r- zM^zp10iL_?3&=vFdHr!+@?WG8MI?%~7xHr0@=_kCs9e*)9X@n zmhs?v-RLIYQ}Lqf)Q?jac@RFKR!DE)Mexn;pmA=ba39%9O{FiZD_pY3svOwk&3^`0 z=8>-+9?77+@ibTLwp7SVD*>MdyA=1&U7tI|clG z_h>JcND@y(o~l~=sGHshFQ!$UmpFOA`7P*I@ugo=(-QQNafR;>^&Q-6Dyy^JyCDi` z^u?Y(d9URma$|;nuvPxHorjq+9W$?nOJF=Nj*ht2O38zd2&-Ghos46I>k@XAIo1?r zBvQOqc{e&Gc+*zZtiBWK^RvGZK3!N9DfpF-D|c5`hyXe6-dVDtx={D@+LlftV`8qD z=Tw26Zi~ZaznFTy)scLld__=DJ_{lu=Jj=(jq;~j8s?I%id0&A^?se@Z!ia>?4G%I zevu>@2@K(Q+pzWhG^3EEJ;~w5TEq92;_)ttizGOkyf_z$W4>?;t9&T?WVshq@bD)I zrLv4%U+KXH(vqCCQ(PiwxYJ#Cbg)prANhu3iq?%a`c(%$nW8PD&O6e+*NR^hXM~(y_`5eoQdC+Zh5M~K zT4Lp^DK~ntaSx*RexXQ{6G*>rEJW(EG3GgZPkgeJ;DGyt#CJ!LAda}MC7!Bm4J?lhQUSOn1hSD@~-I}|_(J*FvA-%@Ad3bow0e}hNK zz3Av{{POA>lug*3aV%sWoJnqrib{)KGoz=v)D2r_J4l254q?YXDB>)XeW52)@ho8C(At2Z&9IfyqE-x?es=H+|%q9e%<@l zuBVRw^Snjei`6C`_>Xy6I{SdOR7zjhXC^6TlKR}$hSIXUC|x4?xw*M%!Z&P!zQt-) z(kAA_M$@|}jnegkp101%Sw-SO7h~DPYEzlvl12H4IYQ#k`jMi!iKV)u-I1Y(#XCQS zcV7vp*|XIb_Ae#=oYFage_L8^>#pGNYq$RXy04l$R5v)oWAy!S2ZJHuJs;xW~W$u4mYhX$(g z)W|5BFqZP$J?Q5>s|E)i+^-cbYI>mP)-L_F?P;y1TA^?0ZSn-){rSW(+ccnMLC zAm`k2iU^w(F`H$4akBtwvS~Il(XRc~U;$HDH+kGE zel4N(4x8S3GB|O~G`IC@x|;WE7L2z()rW`eO(KWC%OEl;Dwi{Dd}(YgMLN1S)?Y?V zcQx~qYD%&#$=#=vb9cRJP)8z`_a0`n6pHjSC9!jpquDSllh?1u4`d4xEt`QGP!)g3 zA>F<@IhEl1uFD+r<;BdY!J`xxvkcD4FM2X%)}30oqQ(^-=KeYF;_=+HncO_A8pUrR zL^?@L(;xe_Ro5wA9QmN`@9R3e5>odfFM5^LfMF^jo@Nq{mxqFqhrz_p#YIVn8)pvb z&+^`h(kV3P-D>B2=`+9J)V8rm-WRv$_;jZ|ICz?>E3>99+2Pt|z>REq#|$GA8Z%}} zGo%xJ29!uma(unV^(GPIreCyTY#D0PVPYt*_iffMBO7WqC=QP7ed<)TlepTqu%CZz z8Ss~{Xd*aXhL2B-`PVy@tEBipG0>()4oNUtSEYTfehQ%3PaHQjv$RzfC?w=j+`eRGl zqq32A<;EPfQ?PNQ{>St|+VRdomy6tWmi1{DRZi?QD0=zUq!Z2NgZR4fV)|OI-&!(= zQcJz=f(qvlo3Lzgku5iydK#fUp@YmbaKX10cto(nFoyNsC|p12g~G_AhX%mnipXvZ z6*dQf7rRQ>q1b_qe977=M1v%h$JUV{<%+wqq|od7 zt5=-}yk_aY)igRkYO5|OxR8?FU&y#OVeXoh%E>smdQU6Jja@}{>KMW2242V0Zd1*b zxH}Om4DeoSRq46xbn5|*d{9jD;}qgDy@5gA z@FY2*6z_BAKwlAt0LNw`hp_+^G0X1}o?fmPoZ)JM*qe!nn6MisW>&)jJ?Xr~Z)+cg zB&f;pD850$~qpE0w(*xCl$Z& zE}oEfHeA~zbv??I>c$jL+Ej{Ill(dSAij$<&csHkld)0EghCg!aPP)eAQ2KDD>^X! zq*Q-Kypd9s-LTb+tr(^6B$|aQ46BP0-7L5|{+Uagr8EAi8lroUhVv_@f^AxxDx=L| za+}4@LGcYvtu=i#;*sJNWpj7ym=j7b%ak{m^dF`G#8r( z>)xj~5_)KMIJv2=Kw*E+MKXF3C>rGP=Hr)`!^wxQ3SuaQ0N zy8D!pQ&M1kG5&E>jSamR*TLx(sh2V)>Za2(EV2!#+k0_b8YOS)bmN zRC5TfWDmGxOu2UA7T7raMa^jR@MjmVr;OIw@cSF?{`!LQYK&rc^_PdvB zaDQIBJ2rZmA=^lo{N}B@hPibNRs1N+?7yFXGF0SDxC==6 ztY;yIpQcMWI_ygajtgKIN8^P0B9~;ejzqzi+WR6e)B61|*-l{_J)sJ%iCFwHZ5A0) zPqYpWgA_d45@cV+ynK>=is_?Zw@14k+BH`;`1A40*~g~@J`FVwvcG%b?X7NR4*rbq zf15sM6uX46*CQuC$I$laID+gOj;BKCW+xV=_@ZLZk60tw)%#zB$lEGDRgxhSu`A&%XyqcF1CP(QwwV1SorA}3;RvK&4W?|%{io$Uw3MXLSkX^-N2k#+nwQYUXl zY?X=q=#!7x5G9w)YZ&{lZD6m!;)2=wA1(Sz6mEI>wGk)#rn(1yTOXgzw{>C5Q@t9H zo)*oKpE0U@1D{bQL7O2{wbtslr6WtF93ZcSOA|6Go7k2E_#Eugp}?nSIi zmnouHBm8)y_@PPjM#48H; z-W9Eyrl-O)g89*JA6f5e9=R9~T)@NDdY6~nLoQ?7UrzW%jpk8`b<*%owKs1chq{FO zL{>J-SA&R`)alAB%1zEluRNK4%gyAz!!qv}QQj9xgRNntrLtnFNwI^nPd>Y;a^!Wt z_5Jko>8nwvCAu#uJ(ss7mZq_Nfvq5AhN};qBfc5w=j%<5?VPGJ6B2K&pq7>h zt$K$jw&PRE|4?qHbu;qhyKX?fQh3%CC;vmUT~kuI{Sudum=vo2b^4*$orr!jtzVt1 zZd_;f-lV9rB_oz!6^lrV7K3)h51%C1V3G^m;cT%gB9`z=;`Gk~Bu^oiXz!;swau3%0k@87cB&tqv7KWx?FW9+@i_k^R*dnfyc4Jq^R_ zk8+M!dm=)eZFTmB2yWm`vX#8IM?-3POu5jPfT5D zzABw$n)|GXr;7W$Ub{B?f-~wXO8M64;A^J7`_z@8eo^zse)`{;t8)z6EMC!aiVX#o zz;kz4_u>mE61`Dnh;-x9q{mIA-dm+}LfVDn2dgTQ4@2n##)W33zvovwpA8faT&;~J z!bzB@Ui1yVUO3K-e4AqXn(=M&%6o5F^@oNRcORA3%9VOECb6gD2T!a@^7KAtj9M*z z<2B9Po*KC^Y6qtY$-63Ajn!QXYb-hmO1ZQjrI3I@V(-i|MB|(y#_OQ3G8T*V7^PO& zX;i4U>nY(pAw4%IzQyQah4{j>S1i62bHfuu{aMw>(!;BrD@f1YBE4nL+gCeh=Rz>< zZ>?}uZWuEv-0yadmeUQ=D19n?zwoqgL$lcaB}}t#M^Chwu1;lNjo>Jk_*5@pR+y~8 zAaJjpppovP7t8gYpVXyzJUnE{t}JYq<>CXDC|Vd2lk0mm7ElGByewk4Jtea8ZZl4? zWdI%bRD+X)lRA*}2{IcMl&TdJSB`~;?HqZ_8ZWHqx<$TI<9BL>ll)wr>=Dm63e%Zd zt-xVgaX;NDt~{afC0=yq3B>&xIQ7BYYtdU-(ZRtmV9e#0v1Tdo^=9HNgusgidsx|t zbT)f{Y$Bp%am?(=B3x!#F=9G5U zaP~fH6Q4{)z+25D2LTI}hd5RRIj>Y`TeZHJj9i;v3EHC7>3*KFhUfnLi8GEFSDC|} z(tw?{&pv1Q^tvG1u(JME{A&7jc1GkA&1RveZ85-@Df6aFBW7!Pq${_~wLm>Z#TOL6 z+~x>)8eUv@hiqB+pudQfa`EAJ>&@z>b%K_=RNGd&&K{5VW5l~RI#ywNL+f!afhr^e z#nw+Wf12-^`n|WETnam4W;R?>KB^knIEz}Vl24X1PCER&^uDC~rS0@47j4t>PJhoy zK2E#p3HTvOJIk8~fTkz!eK{)A%*5ONOPV#uiF926bsG|oXjw=g`WtOq1yA%@m+#SQ zc9z%m7k;6}-z(rOSdpKVZ0=+~*yoQv^QB$j`V`8Y`_3Yx;#QpIeTC~4hRd^`6Zja5Sz;n|k6T6l0=I{g6BgIcvm$3o|agl`=rhNhzD`>F+ zM&@JJ<0kA1R^E5GH+?!^Zt}h@4wuO~l=6JioN?1h-*-qn_H*_GoaSy=a=_Lbeuvlx zK2LAcV(ZvSc5(>cJxkMmonWw&!dDc&*};{3IMSG2{+`n1nO5|>KOSJA+v_R69Qb4K zGcj*sRK=I`%Mn6=haZy$d1^qdPW~$r>&U}Qg-q903l>fI%vz5!MoGAh;6CF6#$+dE zhkcL68>aq3&B5}YFYN~mo_@t!rF*V#&TO1qY8X1ql6vj!jyIlK7=8K1W@h@{ucl`o zXMb+*FZ{wdzz@~0q7xH&+Tli=sq|FI+{rn2sM{0qW%-kHt{i))O>Z>d(jXfs~QDPHDm6rqz1)V6^d{Ng-08CGI#KB4(D7gwe`l6VBfOrZL)e;5Q~sqBq5Bw}mckACZ0n7d zFw3#QC#}|Hh#r2}lVJp{lQb7PVj>xD3SUc8(A0qAUM{_wgd7RH7w*#B;x;X% zLpPOIA6Df4U77e%`QDw#89i=w)(rikA)T}|vAIk!Q8p*pHQmEIof6$Xl4jd= zYUC~YJ)a<`Gt%+k_uR4!B62H1NI5qQjJ0A{uB~@|P?Rkxqf8(cea%E2;~1 z_Pq)iC{X_B=m3bbWvWZGB$A28=iKaMWi&p>jbsfe$R&${`@it<5v-f(CzPK$Adt78 z=A#@J=p5d@`b@=W;sDMC_b+dFYB~NT?Cj$Nbx8RVVXN*zVPpmPdc^fUN8us^$-=Ts zWZIpkyY5Br*69LgsgVtV^&=n37lTO@7S$tv1@GL>dop|TTV;Jv&}7nM>oEEnr7?Tq z>d^iJrgzOm(kb3H<}6lqxxaSjUyvxzHuFPIMX6r0x? zd_?ElSaH$l)n(^wCk};?R}L=HHGMV9Yokdhz~w{bwUCuBzusL$eIQ^~cxzcb|MHSu zDz+-&E<@{C^eq0j7TXiGtPnr9AImp-i8l|dR2Zv95Evp%chwHK3w6wN%ZD1$i>{+M zTqz_PK9oCsaeAhcj(l~9Lz9nOHi}lrGftLxpt}|*%owAxra{f8ZX+vo6v0lxmO%LU zmP>Nt=(v4`qc|yt#{@H!o|jcdpP#+9IR->e9OQr-RnH>QgCn zI6N-2K3I2oDo{(5;)Yc?qm}hs{sy0Xl&9>WbN<87E8KWS`XuT=1QRSUuwa1&8!R|r!37H*Sn$C@02V^95P^jl zEF@qd1q&Hi$iYGZ7D}*CfrT0@G+?0x3msVK8xBO^jsWyB#;hMM1-{t@Qu^Unu)rG- zVDB@W0r=bxhkjTD;19s1A*wO}SAb~50Q?3-mj~e15LJBxw}NQl8~9C#;ts;iA!;)S z*M(^25S$Sh8H95~%*h~J3!>^naKnFu$`D;1g5QFu$}rpkqA!Nwb`Yg}3wMHO$XmE2 zL}%Z^?IEf(g4Qn>L05`13OD*M^uSSc=nqHXl8|=aC|nkzxMOhWZ8M-f2G=Bku6lm| zAPOi1AxLy>1I`G0Z-ElAXN7*p0LYBPi6Q*zIEY`c{0FB2GRNW2%VeMg!adP=q9r## zHi6b>ngDT4>womAfZG#r7Dzt{!o}=C{2~b^j2i3TpPlIf9?S>^SRg3z7X_YxwX#54 zdGW&g2ajPG7}vn){O)pn1a(?IDd<65)_RI zzAYaDi}ruE7zOvU-Tu*L0urat0cTEuUWhzETmkqFdN{AXZRxg2H)tsZdeHgHLkJ-J z4(xZRMejhvav#vp0Cna=0+3Fl9WqWsE%gU+b6^9Lf%rTmZw)#DEU-P^V0%pea#$J& zc>t*1!>J&zJnunkcJM2N;9KV&|NCVJpg04k!JGs}-@_dtP3aj>^Ugg`(*SrrgSKvi zFvc*@<5eJL3Ql=m_kTb7z`#)bt8SrqP*W7={3jp)#Q|g+49LuaH0dEELEVg}0G`gG z+f@qT0!ioij|4IZCuDP6!5=OFLJMdgatolY{cjv~u@DYq{v&%1 z$(l?4wE<-W!07_mRnWZr?}rW;81jF$Rt*a-3fdhsq$CFu5a=*3yh$}S1;_qpaNb|~OM9X3A8iVNdj;%lu)g!O z#tlRG`Ik8V8&A>-7|+OWIs17$qZ*;Qa$qbQBp4Xtf7OsU@!Jz1vkHfw&+tDqFa&-x z(2!*Y6xZOwf7J;Nz^YX^Bc}7Y2>7)M=Qy8PzwN;P{MRbT3EzkFIuBOiq(JgGoCX@h z(Q9DXq5la`O-m%e^4dSM)IKly$QI1!&;K`wJ(hm^Iycc>hf|+dADeeN=L06yl?Vev z(Dd0zly-T0#3Gs4%+oTLH-U2 zceA744tOE2=fi;N1Oj>g*Wp{p!1P=u3Vj8IUg<*QL^V~w92SB(l>RFrTi+o!8j#y3 zTcBy=&vUmZf>Rn`dkR4aW)WPI(0dUB1~9qwd44P(9vfh+sy0Iu(Y0jSfX!4euwvh#hP|C1AaVp}0tCLmNnwxW0J$%4aagMy;PVB1 zOx=bKA;{d42Uvf>xdAtb$(IN8a1nw)55(-AGduwK8*ngi zd<7911pt!}6o*1g#5uzQ>|?=jfoTYNtAKWuEsIG2h#$duVDKwwB;p7z1hf8!(Pcp3 z0Lw?9LCF<#RJW~Rc!0n+uyLzb{%af;z{P<;0IlEP2&@^!|8N5sQWdfj12Qa^brsGy< zna+2(66}#RnsKuNJ8k+q=qJP$jhNg*Tk&E31Qt)>l0f+>Tm<$Ke2O>)AIHhvA$kee zcgDm8Zd^nV1NTng*Z}YYtf2Nb+C!onCMl4^1cr?D6AIZI4OiU8q(_Hy2ZA^Kp}eUA zGe5!Sa+N@c@q;mhp_BRg7yLTxayXj7yN}5P!1w>H%k~VkR*n2EqXFiB!D)fGa7=RI ze+OE@{evj9LR&Z{UFt;yAB;ZnH$a>ki;#gmN%{l$ju3}QWTF8ROoTcNI~&dPVj@&w zMLB53KNC~%{9y>)>WS>Xs+7t{YZ2st4IPGobtV;}kz09~lz|Tv^euKG;^S|j1Yopu|7t_ zfq1&|;Rn3sSgQiKp> ziw|s)AS7Y71dy^2AcG5|LVNQg1w&dTg5W@yD=9=JfGcER8^G56%isW2WZ>ALq51>i zAV-M6Bx!(8RAA6Kvfy+jql5_ngk%i=%-KTfzv3jM|67$482b)RD|HI6ek_K+Wz@hP z9k?Q%kIZIBfs6^Qun31yL(2&{z)lIm*v!9SQs5&U*!FXiWJt!r^4ljKFi(k4fJt6} z5PpD!2}TBNmHj&;oT)%<5e~ErmldpFZs1?pBqS@i2+5paxI$>118M{w@Q@mu(YeCE zkt;9*Q8aUf7C{Mk(tz3dD)9&M`2&IqJ*|&vK&K8;zh%m>D%sx*1<*kY&Ycemz!Duo z006_L2Bro;kLT;4CLL(1qV!wFif*up;$Nw5QGpa3VcqIzw;3uh3LuIe98Ja7pdRD~ zzi9;bj|F;!EX+>(59BHwp$I$D`2%^Q1?DQf{NH@MgM;-;>i?m@f&lZ-X#59~U;twP zo+7~7?9G0|xWHEgLKFtO@f(qbQCR+F@PH-;gcMBmCWO!f;AVyokXpcqff5{WEQ>IL zwVK}gTZRj8Tf)xg6(7vh8ZCRv2u}YN+uw>LKaji?F0~MhakK z0VQjW00kG~G7teVl1@Ms3qlNL=>)8^Af#b2PUu<_aTxFcr3;`&_dm!10RuJ=3n4%M zK}O`s2!MAN5WFxcXS9{B8yP9U!wTvI|ASnJBEtqeA*ALXB*~l{4`^lut#RcvI8daFfUX=S_CFgS zbo%0OMLVk$X21jD*+J8ru0SI@;u0*%6`dPa4ulk@Inc&|5Csyze_)}vA%Pdn(i5U` z0Ov8B47kS$E`A9 za6$Ws{LSD4GTdP8dl6`)@&ULU@Ld8&uCN4XTEY#QW+k9yw_-urHa8fvP%;`3<^k6? z?X=$v9uUI=&fpgrXv6~m*UQiWa4a74fPSd6(69h6I6wVz(M%LC*un0F5Q6}O^T2r{ z=n5MA-~|oLOCXpHkmdtZ(hZF8A=rVW5^!i zW;7$y2qOZn@_|0PE`qvit!TKi8Ab>Y^Mj39>41<6z>C))0ydo-@a6{o018G>c236Tw!p4ISPZS zA~+CZ2y-KVC;~Vj#3BS3L_moE>2HJ@-8z&A*g7_v-!LJtPl5H1>>DJjLi`~Mr2{<) zKL@jd!+`bY4(h`Eht?xeaO*Q-`vch#1xM94o<9%`F>p$E@c)4%@?y~dC(@vAB9Xs* zdy4;|B`1PK1;oDqwRpwB=)h;+|C;D54tCC*EE>s{0u`B2pyC{)=%V-=#s%mlph2$s z2jVFKCK0%bM$FZ)DA1-KB|y_TZ8Yq83EZPV z8a5a5yUV9pJl*0iOL{` z4bYSYt1GENGljCCnol#tSi`ouAj%Fn%7NgcJ~U(54QApzpk+BQAo@`>ygCF9$HXBx zA#eej3##&jff@z?-0>YGszhN9e=L&cPAv#89aQG054PdGN*U2=b-E@kU zkt!mTVTEUC#$6G7{=I<(u<9TfQdzL6f%$-c*QXst(C9w?xd>oa0w=LLF`6MFz$Qnp zb$}A6Gf0kxlSr_^oi*ZL`x8j!K!cVED}(iXrAISy%HVjhV?;As%7`m4`3q=9T?Oot zd3H3Dt^y`JkQ>b$sDL{?&i{3F-2qixPxr?HufS^{b(d;Ecq(FV5nDnmpx8yR$Jns< z-n&?$GL{&@E{bB*FE)z38)B~r_Aa*A@jG|#W7(Jdk>@!xckbM|bL;MEIS!isB>pI@ zuEar3l&GV=;qYA^Kv#c4wWX^oG6RWG@O^kq6*D#p`S+}j!ZZ{dq7>jx@+j!=GweK% z;dFXaCm(9E5rO}U(NV1w+C8Z;IE!HPF68* z$2)m4OSYxayBTWPIipx1DH;pr#Hmgi>f8)@X`cTdQCc&s6it`fv9*OJINl;{2!1+K zd^Fm*J4MB0M58Ys;lRpt%rRoL@Y`mUctQ-KbY>f87H&aC<;I}yxOB$&Q9zoL7Y*uN zole*&y5rm-uk@QBa}X$~1-8$xnqx}qmBI8n3-u3i>#JH|XzV*i z`LUuuO*-u4OQu*<)$j~s0;oeQ%ACarW?*wHl4ZzM2094Yx0nH6O8(;HLRl>_qxNcv zM)k|Hrz3?Y_f^cEeB|QS$>_JJR`9yq6E4eZg~oh(0GYfdZDq0wFBDm{koZ<*q-AR? zIXge7mdlBmF$;a(=Mmt0(w2u5bz^M&YI5Qx^*^L`n z)Ikhzh$c%MCd8u_+&#<;Kt?iM{CfeeJ zB$9VyAL3BGE{e-4bi}%{77Hv>oZC^Xi+h3KPDq{y9T9+^TiGnMf`z7?kUY=YDvU_! zose7eI&!9YduMmj#e?zcVq@YFwmaQ9Slb1mNnVXUJrUZ?!Pd%miVTvbI_v0Q z7qp=Ej3UB^5*HVRu1Z(t)NEcbp(`ApJD-EtInD+)qgaJiixoyg{`l5Q=(3zM1G*tt z>##bbX*7A2vxX7~J#%gZoO{|0mNT$UGg(k~o4oBOU08#h}h1 z&RBlI(v*i4-&R0FTMju(Y(2ILJx;6Wo4+6$XU}nF;c4`8{a(<)G=ik@r3L4au1|NN zr5k&}pQE=FT1$!7(W}pyc8`2cXXm3I%IBgT7$z24k#E;?h4&RLf8MqGe}&D*FBIBB z-+#qesri;OvAxA6Lfx+laHr$FA%5vVEl0w)^g?GZw%k~St1b$oqp^LU)6v2ic;rMu zMvaduvY~Do^*~DWP^m`rMHk|9E>|EI9_+0#(u%%_QmSZAORRERN{ju_l9i=Y3f+P< z65SbA)SVNV!jB>L3MTR?r7`g(^Bz-JT#+mI^v8T~tqKP#BQ)NsC1hoPD2CPKvcLNy zjT-*IL1+RJbz40SCMIBfjA+C`jrtll8a=PbnKuboX+o&`0A$nSMjA7_4a6)DC_HS+ zOQg5f=xO=@T==$Wp<-SQz?@pHwTfvmP>d2@wzDwC47746l5XZ=&J+&CFj~Ka zgHFTHDFw?oXtE5xp8pNGfj+hhvz9A#sA`RfAC9^_R&m)C(gd;Q*?c|3WPh&avbYhV zD@|IdDM4xbp%65JUCgE^vY&)+>p93u(cl692weM&rr43_zuFs7NbbKCTkJwqxQ&%) zDSSw0zY=AQ#JJGx;o$U6je!D2!E@hzj1lS99vDuXjsQsq?d(j>VhX;LeH@8$b`(po zV=89CVU0WsSg6@(G^h}l84{~apYx% zi4v^W6`&*iSh1SJK1vxYhS01V$l?|^;Nq9tb}n|y=Oy5xhPsZ$i6uN2Uiq#migo^2 zxc2Vhf3-@EL)|U~Dth8LZ2xlJs+iny7)P;qm~4vy4zmAha1BuiH|Bk^bEDv^O6&LW zNS)RHqeF>2b{hIV9%HqflZxpw0ky^GR7~asj0bd0ajEk^nAx_{Dzpe! z7-x!_0-XVsIa9Hs)|a+VfzGb#3gbePs%VX>lbJXb?ihaH3N5ChbwlfOFsZ)Qg(B-} z<-MGRt~14qMvBar2AqV;HKu`H`7@^zrismjA<-OEX`*!}3WLspXuDOy+QHASKMij_1QDdpd+KCpE^{)%*MSVy&dv*gs^w(rTFj zFX}K0Q7Ad(Kk|a|vr3lyT+0a|Jkkc8n5u^)CIdGqY z?MeCN91PCTI#ItlaR1UO6|-`=*0!&@J_mM|tWnA0en+kc%|&R&tW(kTl93XB>_gRk z*4wrC+$NP))?DnvdT&)R6*i-Xh71KB!wVa=a%1`W5XcN7u zjQBOlu&Z}_wxZy}9t2xx>3meM_$a4O&Bu{nbCLmxtcjR^a?WzF^c2!np8e(1;D$t$ zdVikDx(ipYvR^ATUw}FMx0?)Z#hOwlu%x0qLZOIPk!``Uk2Icii%8R`)dnjFuH3MPB%}&1?9J8 znA?0BC`_cVwm>8i0-eF*3DNg52IfR<( zE=NsyT{%5$IW}vaJt%kuo@+krf*{D7aOV}!dDDl{U4+yGn!#fo1L+sbfyqM zu4}N^58cf{t(`hE?W+L)_wBLM4%o*O%F(Gc7|Y(796Z~vlX!S~B_li?k1)E2Q2hiK zTT-BV_pAauD5MYWsJEqHC%%v>t;Lt5k1o!7GS-E{_nY4=)m&!}7uJlA0i zbh^iZ-+d&sd=s~F9cpd$NTEIWI`9Rw!$=yk9(Tj_A0vI`#k$>kC|`NWm6M<8476rF zwv+`Fyg~F!O2G!|`Fhmf@e|XKDBxcVhnNkB@ytTTh}7hZ&Vz6ziHpPyF!dB~=xjlk zJ>P)QILn!X$c>mr%j!8;un|+;HG=|N>D5NmumlfDS;5FnNSs<89DK3p-Du7?Y)jHN zVIQ37&FRS=dUyVaTfXUV-HeJuBrdDJ8Qr`qhygzu?XNGPx{RYw2ElBH|RTu~)V=BgCgZdok>%v3U^unIXboEfzh4cy$0gY#RVn-|AH$Tmo(cIIHhHngKgcMiUE*5kQd zWz^KayPdN+zi8Zu^G9}ar=g0|ed>(b!YUkQxH1HJ9od*`Jg)?cOpECRx(hE7Vg9hIe0w-ZG@KF z*snyD|HQ50zgV*w*uM=mV6Tr8Y`Wfp*IoI4>!)lbw_WJHn}4#!|1YjwVHZYts{fr zNUx=uR}jP;R(Sngg*H;zw%C!>`U~|ZK2>NB8h8}ZS;FY)Zxq@{SN_5xUf~O83O?wu z=iV*4QOsV^S6KXw(^L0~RUD>}Wgn);p9|sNtp>35elKi2aw4~VV!Yt4XTK%swzG@8 z7sGoECeA$Hhe*yW!GJ`O`_Ziry*NlM;o{8~sEqwERZ`;gLvI%^wjLKvs z*aJvar&0=VqBDUmB`D(nf^Z^)({oF?6kRTdxTwc>gq2<&g^`X2VI&u?zc7$~5aTDh zssglR&Ol;qufZ8hCLRIy%s?(LsH0*IWMGUouct6|g~&zO)AzzJnB?C*d%rHs4{KxittKSbQFI9%koR zzmZ(4!Z1X=xQ|XBM%Ayz$g-p(=;HA4MSpgpPDcp4067<%V*s!d~)i-m1EEi`hgo#!{V zGX+0N-s<8>^^U{nzCRfw()b-NA(YvjyeCs+j`@1xeA2$V86L&>FZgz z)zq1?bKu3AbJ%w@K8GCXuUDA5!Um%PG*oyF8^p?PDyH*!ENvHjIFs`?M(j#YS6@1F z9+v0(+0%HO{WnHKdXS19_cucLuC&7ZAp9As0B5R@BUW{oPgyzWDA{_OFjsfdCSjV~ zkR$ryW#{03;QN{KuKs-S)c`uqtzv6xbcAcL>cEr0gz42~p*JP}BSttTn+(*{)lizh zNh%-xM56)I!bLn6n}qGrMJ$3*7sSdA?N8;_&wO5r;JO8*mZ1wE~4vKl{0v$ zRYUSpK5$PM4w> zc>^H|9HwGc-$25wAFg5s4KbK`SBp2{!c%Odl=2;JqI^T_rfkg5!WCS+C}QarrjB1H zDvX9A#u+r!ArG;POEaj~tITw!g-@Jr!N)eZi(nui-C(-_{qZ*Tw52HfHkRENy9^$* zw>)fY04wa>&y>3fwKCan5H-rhycuwf0bk0yguats8JC0j_=;VnF*g(~1L3{TNT1CyXU0Rc z{&YT!rg;{NobO_4cjTk6HaSu^(WP4`KhrYKqimWkKLDx}Xw3O2h_DzpK zml(+DR*x`iog2czf`LX)+Rw!MhjFIx5wf=WNSp3sgkk7p4w4^>O@&QU6yQdlPaqyX zO<^pQ9wvFwoF|A<$(fwac!Jpi4^U+%%}=pMDp^rZj!7glluz@^7zTxzuSzW~586 zP`>(E6;rDK)8WkXDrR{BE`4=)4y)90^_*{>fN-eUbf^OOM`X&IBr`>OHGCEkuK{r>ED+Rto5c>R&hP=l*HS!(A-U0{t@6bHFUL#8)-$N}! z!$4ah&XtqT-$UaM69@fWO|}Km;v_lK#D6j9zqxT)#=m&7WcFa76qWmc7T*q~?w`=W z zmAot4J3#sPZk9)Q8{a{yCVbq>!3_tgrVx_B0shI@dP0*-4qOf(8sNDg7c;JHdWS(-%jnict0x10|`IlN2G;y37DBKAoiM zLg+PK!3zf3-Qu9GGd!D`#{u5Oj}#`{Re+9OF{b-{71KfkrrJXlvqK}*6=pnEG1<>e zI`Yy=m4wev|4Yjsf5?;AY%Rhyu9PD+NIwAm%gn- zjKehWad~V)ko(l&jJ~?rl^o5evwkgwai?qpijFp;s7oDA?>0-d zh4A_uSS-j7b3+aWGmzhigB*+WgYc~h2jOl2{h~RT?`v!BP`L%0Bt@~FCmRkURLoIN z42O5vDcN-5gwTl!aG_)`=|{ng?UGIGLb(%=4MEo zr&wR~<`GhWmePF@j29bKjGKr)67Uj*CN zRN4spB-T2)$bCOVXZT5l!3+22I9PGoY^28zd~N-{#~(%8UZ8*crB*^Nz5wxu!|QX* z71-X=DhT-7PZ+Z|08MCmm76eMg4gWhdp_q^3WSO2Hz_3$iv0pHb%)<(pp~Gx!^yKZ zQD>bbJCg$D7$4fk5K`31X+p8cH@W3=%5+m9#7*q1g2OMPHMe}C|OICamoSx2D}X4aCDl|Gcjisg^_l-Yjq3{}fd(3ZZi zi}|Mlu5juFyp?cqKP~GCpU`DR8C0 z4>QN`wODDY^CyBUFINzR72F-j!cP!7yr=vyjE6fy- zKcqZr^I9NN{&ah;C4^d307Z*rstWC3C>+n(7!HM`WyO?% zrq?Wr)RS=3@4mt&ytWM0qDI?jYF-h-TB|HH zof9dtPA%1^9OD^(bG^)4X-A3$PctImNdHYXbCK&U?(DFG`KA(7Q&VL=loBf;9UElH wD1dS+Nl}iGhl-J&%$ewfD|}if0<`}@oeb-0njB)zW@LL delta 32126 zcmZU52Rzl^|G#_fy~n+>$==y}Z`pe!dv6)lMM%izO}1o(NF}2oA=y%7WmQC|WK{A$ z*X`rW@Beu`&gbRze2w!uuXE1poVWK|?dv`dKl+du>0#p#VPO$qVZHXwAmN4gd1pwC zga2od!dTHn7{-StwlHBpnp0r6U}(yNU42Bya9oe54BqP_ic1i2M575C$k1jY4B}{Y zSB5L(Xu8auM1qC`&K<#b&e_A!FpkvoBdZ?ik4Lm#_RJC9FaPL>zovNYh!Q9d9?=Pv z@FQxh#zBL27iM`BYMvzzntNd>fF@g(67bjFS=?4~qx!tBg2USfW|}R^ljM zOKL5et8{Sw{#aE{U*ES=wH>_ttX6mLaFx=fBoS(qd9}Z{&x{%LYZDGwuiD{$7?m2? z_IVqBTkp^~?UI{nCWnl{;`My1euTsEgUx6P^)9q3cL zr=nJJ?va`NXn-p6yt$7zLv~MU5{m>0N^dDY=`&KZ;+tysd1Oz;w`L;KE>BMyb1USK zc9+G1hcy39d*+sk^16lCLMP--<1oIZ8g2v8`S^PmUZ!w-_`!emOv7GI(&~Gnp5Rm_ z#_Q&8>-Skx9)G&OSnQ;OfBRFop31Y2QSEgV7tVgh=i(sax**k<@=BEd$B*V@&3Ss% z!K?ICoR6^__Rq|M;JCqG)5k`w27B%l8WGOYHxc2dE$<9qze(iygeoiVf$prmcB2Ce+9_;MbgqW(S z#1bgc>@}?6?7}VTzw=17CuaI5eBWprl&2FMwKmlE<9$`P_vrS#OKQYW*JG2AScB%3 zu>p^v7X3^8Bn&OyS^3oim%azJ|A|oiKA81cg^;%JzV)lylZ=MXFBe!7B`}g?Dc-(` zx{(0U$uulk-no92M&nl3ciS%Ov_cWD7j%E58w=Z0Ebra8?I*r2ogXc`FZ8kf9X(jGei^-bqfe6D zis`lgZ`K`xH^_Mt-|GX-2WlKzU#QE*vSbbK$(O$Ir!qZ9wzWZ@na9ET@Jaf3kLuV4 zAxh^fFQ-Id`nZy+i8z7Ibq>y=hIFFOA~*S65S+A`S4{7f{ZY{+xA0u2&-xswmCbo3 zfPPn-Z|^DDU#MfhMOtHc$9wzitBMtldZn0Ki#VRxgb!%0Rjd*wn2=pm{^c#jA| zuI_yhnV0!Gnp{cYrSLLR;pKzIz{}3b2FiEHIzD)Ah{Zbz27jLVJm;VPTP5nkB-LKy z8^Ll%lRQUTx`S%wiw(JQKk%Rr-G>Pdf9B$b$Gs5WLeBA{w@j)Pauf0SnY|> zHATSQ5Rm4}_V2OL)Y9n_nr11vssWP24HL}@2%|i%tOTI4HjlY(!qK{29!I*(cYVBI zXrA8B9|uhngG7$_w%}_=dP-rTNAywnr6VdF)p$e~u9P3q_~^1D%5#m95N%(WT5x19 zlfHxYmnE8`hla1_#KOs5gYqXuoKZvp!@_z4%Zi!i$_j8LfXEgQ%+1z$$RoSZ{0Hcg zo5f$K3P`hm;pS0=y-@s`0PRl6RTLUoLJ*uDRA80aQ4qZ~9r%>!UM5l`a2l|%u+~5m z%UW<{hf0?b#3)WtA!i?_;NY7n21GAJDB?eONIWFkArP{=!H~2F`-4rt_=5T+!*4YM zRvm>xV)FU2mx=TN2@z>AX`4T<%EJUk+%J$Qs0NAM%<-~(mqbw_dDoh2BUWU_%bL;h z%b(KAPC_JvPF_AkjF$xKfBf;{+SQ%;^uwpGUWRcv`P13$^M7Amb1S68i>lADpLikj zkzjRVz`HE?s=TFcH2+p)(V@u7B^{f@LVD$$5iVDbqGf%FRB`kdP()A z3;0L|vfSCLK7aWNqm0(dH*%$D$Ii{gZ*%W)8b6-VKX2%U3TAoMx;s>q|LpJn(s?ZZ zc}pg>SKDI&YP~W79HwN;9EoX`Vk41U z|8R5h?FpY@@&So^K6o!`&!0c=BCNUG1q$a-^|~ z93!jb>kA{oo)(3^%9e2FriR|XN0g8zD!f&#EI6?;@GS#XsMrwrr*YYTKc@P(n`}_| zM*jNbjo0?HDtD8YW$vg|n%MUZTAzP5fQ zbz|vu-KGKgGX9_R8rk-*X{UTOrKojm@XN0-^H@=78VoY=>pj*LY!?<(mnoW|cY)Y9 zB>k7&8jBf~P`7%>5f2#f$ZwRVRvl30jLi5CgAf?v<;{YiPC#PPKxXHVuv3A9)D zQds*B`@*&PDjpZ3a=bf{37lOtzi=FSX>~7TjEGs!be}t8S8Dr{-Tu7zb*foEF67eP zwwx9AHXd`ne$>h(nm?Np$WnEozXYRMre6sndJh$#W@s?|xHb=e9cw z`##T_#Kk991=hIi{F;WCyMKMZT_=?ox?uHA<~29nXQYE~liO5X&8Py8melK|6o2Ds zjg$!<`qW^D$VyMCXq+;(I_H$9{`b}Fe$yY9B=V!0WIB?RBLJ@MJCs=gEz+nPj%VI7 z9g;->*&z zHuXEKUZY+}I=*@>Z{es9yH^hAAAOK&CTw>hoxiI1d(Qvr=I+(aOHV&+KKcG7co_RJ z^P%}@sy^4*z;Y^4QT@e=Xv5dicTnZ3b=_M+h?bgab-8BtFvRDMtE3%Wd+jcALRVSq_EQxKHH<6W4*eUTYnex3` zdLy=B+5{`1eDymXhx}EzQMbe^o^b7f67ww?QKhP+U=WQ`&YLm+N2?;ww^XuH1ZSF7SE*`YWoh@VctujgAaMEh|T2YR;G#O$iEW6HGUR;(YCE@#l zHguhBIvFo+G}Y?t+ppIKXNnq8^-khkPSYms*e^WVl>*((D~(bab1#ZyA|~pG=6Ejo z@QuU_)N+URj$a>3nD(UPcQV+mR;M zzdPlD!=m+O!OT4^7xmP3*Pp&s^2B;%{Qy{V+M51}L;3cQgyZf)Xpd+G(U( zJ#DzM${|A-{7TIKWrftE24!#N{e&AS^j2H)?LU5L3gxz6HB#NLC?47q6A;)XyNM*c zXZZR6VzX&SM`x$W;J3D_Ho=qVfejrF#&;NbDQsZ}o?rL6OtsP44$4g0~{GD~V;?24$$~1ttPz z-GAs6I;Z8GW{H_)*r}U+s#XGT$sQm z7M(U^Y`e1{wO60;VPO~fH(E&-_4smAvok`xh^EEe+*V9yRzXg`uM7D%PU*)Z!s#xj z3>U>kVXAj)7GiZ(Z*~Z!E)U%E+0q+(S8FR6zfROQk@Xh3{E@sDB8>8_B4=!! zZOYkDNyhCcZS+`Bw#&2h=*(a$}DX5Geg6|jmF=Qb}H(}i#|%0VdL%TK$QRz zY^sK^^^mCmzo3B|gk3UM6CLe$cqhcEoqMOXLg?nUn_P`ECVKRYLT$1VmY8hGMyU$h zzEWQ?(^BpFZhD`!EcQ$1>xZ$Z?75*YO)Dk>^N8illtUW3OY|F7gax_M1LTB+2AX2j z3ZhP$*s7|Y!5-(nq^_kx%O7Q2)(pjv^d(H6l_L0?tHV}`h1jT8g@($sSfnxoyL5l~ z##Qf3)IYGk*eX%)^jkt#LS_zWts~r+>F3!#{A@8;@?lsl~Z*7DhK z$Xz|6js1T3^$($;p@a>3@hY9TFO!C41s0|*p5=L0#=|)r-~UDXN`|7Vd8~nDiLZ?V z<9@D&?3&zguaUA;xm@H6YGl3GY!^GrROkeO_WQ{?-CsW!v`4s_GS=qn2g3=F(vR3Q zIKNUv^2-M~(UZSTh`rSm&54T2sSA2oA$?D!^KQ0TT}DQ-V1Q_4bv|DRpPOhlBP8OZ zGV0}^?zkM+y`AKa&*PAskxUrR)6i*~h-XzW99g#d!`D5rE|u|V?`7`|0rp+*ii;|A z7PK>Tmjk=^q_JP`x#NF)HZ!RnC_pI~r_>xA8|T2X!EuK(QYba>V&y*Sd!{tGdN%aC2+s_Z|lLC7AM-?0$vsFGNCx0?i{=KDP5O$nLgTXGT4Y}xB7Qt&1nkk zIsClSMcHso#M_9qbz4N24K-IQ{H^Z0pmm+XV~J#`9UtDo#Uz;yPfKfOk69Y87N0AW zYxf@qky#e0Tygd|pizalC?;=tvRF?rOo_yM#muC4_sG~isa$7UKWpo%=S)|SN+kF> zko4zM$p+_zI?G*cNt*qHxa+EaOS%~4fLWAa?`T5&4{mCDv^ z!DlZnZWW4#&E*fR6m`OH7GmAbDKWQDPc5h!#5L@e6~%>75k0Fac4WR`I*gYNxzM+F&iJsp$dWPgL6omplA_%jFU!orZo8Q00IeJ$7&`oso+`IOw7Wd!7VeV%H5fS#$ zFA|R)cV~v4phe9E<2UipDtyyAXf|~E8Tx@SOLEQx%_hxl96diqE_5DIh2@DOE4nY; zNBr#i5b$u{}5zmM0z-mR45T0Us2-g`k6m zNnj+XK@(~fioXfUl7xEYl(ZBmqj8EH2|RWxbv1%myocI2{lpL7lQ=mwXHCs2uXcYP z!GGR-rsDNA@_9Au9RWhC?id!+oZ^k*jlYrLKh)v=KJjw~hlBu$IB&|ruAd@)7kFX| z9@F-S_~~sJGF-|?pGoBGBe?jO`{t(Jw;0abD57(?Xx$y^TgU}2;Xg) za(4N_pCQg!a<|yNgw8g!O_fhB-nrsxoh?82N=)5_z0xnggeNHNS$nmVjdpGSlg!4) zf&(Z%Hcj2~Rffw$*-=ocI^*m}OGrZdogksZ+QtWMdv2|bQ*^KW69qf$i-ZL_@`UdR zeVQv74_bJb^h29Byn_9vDDD!USa><>-HSx$&Gnb^V?Xl+{(Cc1)a8%^uSmu?+jUG}w!xEYSoEt6YNuLLvU^KZS}#+K$4@Tg*JOf+#Y|d5 z?^?sV*VmD(p#7pi)MFi4?^cv#~rrSHp< zAl+Z*D+2$LN+>_)) zxLb#*-CN9pC7LwJa1x1GFmN%zfT-J>U@*>iSn4UBi@TX>Eui6Y+FTf zWZP6XM~H%mGxjwW$FHc_y>PXW``G1+yRVPR4H9ln9%5OU(g?sOEU^ruoa!tczWz-4 zXZ|Zo^-QIa15(`}@-LT^cyCBYvyLjhSns9H%w$kc>e-Vf{nSMwR!{P4^+UX}7(=NG z9$9AJDBs{kMT_C2XX=(@!?axI=E-P&F{o$kaR=4Wwq6_IVtN_ph|ec>w#IDX8M-{wsfC)71jB`M@(&MVbc}jddu%wT=dT& zS^mKO@+=kIr{em3aj|PA$}Mb2W;bM-Md{fU{H-%<%y#lMWl654#kcM+mZh50dkY~+ z)|u)P-{D@HrkBsKer+_Hn?HUJvF^5(i0WKjzHuRM^|k(bT7rV{neTJahM(FZ2Jp2y z(%qC4LqZ(+685iL6*6sbE&l3iQ-M1X(K)~An$IJP-H=^s+dkW&-IXDm6F;`#NqOC7 zYvJ9yPyLOrqFTw`R#ypS)2Y#h{Zh}YRn*y|9ekY?r|GY0?2_;()7jK;g-2$cc+eAd z-)v<`%q*m}j77n#{aJ97{|{rzWG2s`J?CdP#jg%s*?YXYgy*FwZ(3;-Ji0xq`n>T6 zN>yY4c`x93^EvsIq8nD?K7X4fKh6gVWY@M#`w~s1*ih!K-n+DVr_m{&CQg95V%^mB zUUYuCS(WE*f}hxzAD#4#7k-HgnEIF&rlGjJ6Kb`XD!yL8ZI1h+N9H#QUy!q6SbM^K zW$77n;pN!3i8oo<+G!chRfjIdmr~>4JS+bW4Z<^G@ZL-4JdWp*SBt(mCdL|^$z+QR zffgI71gY-pg`}kuhO?0OV8>VZ`kB8P`4!-5E=cb9C!;bb=hK4v{VPQs3K@Sq*x$Db z8m6927nB!Tqw<4>3mrUvC44sejeGLoG16R2O$%wj#lmVOhRB&=1}KZQU}|%k!`TOe znJ&Mt-swnw`=};8S5YKetE}wN2wg>!2~A+L^_cIQ*|v7V((35yMD|i1VXbG5FtgZ7oqaZ132wU?1)WG6**r|4CGH&AxCuqInbM@7N}cFUH+G zA114`Pf);Fpd;DFVvx7^wh~+0Dd8qt=eD!py*F{zlEQk89n*&%fB5O_SzN9UZZZ|; zx@Bbqn7t578&y#z?WspyjW8FB zGzkoO!(fxg&q|I+aQj(BGyTpdMlCtw5lMlCSmC3zmE5m!X;xm7quKdGL#f4$u000a zK2=LQfzzXI>j8(H-&VrjJbCwJRuj?JoSQp3_<-q+I}a}(Jif0oR1H`V7#`3iRrbYtZS!?-8w>3QV# zszay=sy+M1NVxfLaZ}!&{bWa69wFxJgSYaBx=ClyxLUjSj7AYN%Gho8T9DqZbVQDN zc_VyRK;=#p_f(`&>5DP9ffS3!(Wn7^+gi!eW~-o7C+vyV6lR~yZ!}@AR@9*szYsz* zp*FbKJLhY0mM$Gh)Km^x-(=^~1F5Pw3v<7nB_Ep4PHCC!xOvH?u)AGsNHj8S^tZI| z61H6_b$TErR(mPR_skNY4ZGYlgBR*va1v(u$vf@ z?XU`$WxMf8>!EY%U832ci(O3PGdC}JU-ZAMYdSle<7}e#hW1)==eyR;nzPPd7{)DZ z%13!xI;V2Gv+`#OP)~ksclz8OmNz0H|6ofH=egXe`K!uyW6|%bh1u4@B@SGP7=rhM z=WZ!eYG8S*`bx2>w#*ae%&JosERK-#L=SpA91+Dbpk%lR(F>;;6`l675= z^rLjkvnJ&)EPSfCXXV#l2`!B_l8`P>QT?LRaJ6jUpt#k0KllNPN(ryveNkP^@Qi`> z02>9blL&bP*&RyW6f1`x^PmEjF*0S?H-_FFl2n`=bJ*cn>gWq zA|qZy9O2R5o>*mBPb#bQ6USN%IJ*vU3_892G?p;7*=RG5q|x-o@pJzA={_F2cVTav zcIXIwU2(7T8x>wFd(^dF^B%7X`87YG0I95YF{?RQrW#U<%zA$w;&*s!*J5NIT#opx zS)KouAUFL?ol3^tPMX{-1$E>ZO)i=-&Q#560u}CzDs5V7e5Wk#o1SOluPsTdF#QoQ zT=M=huSEGPKJuskcGht_(PTzcLxa1KZXjc07Ew)M z`P%6D>da4@s@X;ogAJTB@ivPD7ov?6>Kp0LJEzyig$%z{FA9gNZCjKY*FE=B)gZXR zx6Wo3%e>Gn!geEUOHPwu--G4Z#cZSK$!K$)nhrG$ew|6n<-f+Rhc^|@EuH7Q5vJ4= zl=CEqD3^b__twL~GNYe&aUp}$(&TiSe#gp@Q3#Sd(5BM+5oM^H6S9}DMPZy@MR zyM3+LJnmg)z}I=l#p_L^#VFY6s$Ny)@!cIMe=GY2MQQ z_0Jqs6pNsOvuhi(lG{qM#hNg~t-o_IRGg(GpbNY&_g;T;y;8iHl3(!MyQjW-j#Ii{ z`{{grabM$&T8t)<*FJh^arcq=v`xK*_XnH$$f2V5vwip3aP*%l?9PbqD(w~q4;My# z+G1>(!J8)u%w+LJJ&x(y&AVLEcT@lB^X2O>b}8JE)Y+@+oesHQT{pA_bnd5B@hWLH zmQ+cJUy5$E&1=tTWf9+{{^aMp5%!5p>=J(PrTeiZzXIvWzHL(kUlMP<-uFat8$W=B zEb3b`mSNX{gFMCaYkRHq&j?ECp1BOD)h${wPoiS5n0xL$3FkybNBCS~WOkLh+O;fN ztmqKSy=D99YVYzcO#VjI-s&6J9~jEzJ9n-^*Ya>jf3tq^j|E{x`OPlk?*8k-S+=w+ z>%n;+$(FhupM)EiuG@uLrPbyZCtkYyi4Jy0fq5b&H_z+Vt<`Ql_}lkfUjy}$k+nG@ zI7wYM!b_NG^CmJxQ01K!@2eOqY1hSHsOXvE7ZeoG;oVgCe?c@wd`&ROO8=D=JMyh| z_n&X+J1;JHxQb1&S*t?b!2%94#dPBDy&W#vOqC*hR=J;r1n+p<)49uC`P13}{*cLr z6VVZ_O+NJ{F?sa~c4q^dL2^2NZbo8v1rwEMNr&jRhmx9a0w-#&Q8Q5Nme`rTq*q_+ z;mvX{ZgkGmNz{B1eKwL~Ib? z3O@|?fBUXc^5u1*MjurjIXV3ElC;(bvimdg-lHV@+h2|za2Hk! z8?aetNbmp7khG>+W^|xAC3)8Lh4Uo0{h6>-X^OXXlD}76@>a6@i*BzQhImAFzils+_Y-$X0jFp+P{L&MKdU(O`YAUP9OZr+rTfMd-z2x#eXOva;QGT!Jo*n^2*w-B_nbbD7a4thRckZgPCa5@ zJ3S{fNMoTM)`JZc}=gAYoCF)#pN$j67@FsD`36ZMv2OHUIdOx~^cG zlN;K$F{R__l>B?h_g28m>hpbvl`;+Z?PC-%?^>$Jj5ozn*%7|A9bS{VVlU(q@Xn9z zJnW?PBzc?IbK@e8Vc25ZS(P6?&^xEy5UmK^pH7i~tBMRQFFojuE6z9!)N8|*{}Q}G zYar;S%Ysaku&|dz#j;EIUrh8dX$We8vNVZ{rXNN=ICrJ@X)wD+tZW9)E=lm3?0t!< zez6sy@^*H9n`ybyc)^V*j{B_jrp`LPf7GQH*P?&1nKHg3d0`mppZ|6G@si9_x#(zS zJ(gtyKHs-GdTF@r*6O*?=fsr;iLQg~%_A#?b((@K^*4uBV4NK~?R<$N7|HR!X$nt(Rz)_@N<{(3+qWP%xJ)qNhlIsOt~e#BjY@d`2CUKsZ(MxNhiI+sLF^G zL6RqKKvdV&J><@d64mI0Oq%S3`!u@wG-AB0p6?a2tBjn2b9l|(&s5OV`uYVCNk~d@ z#n(t)G9h}CC>Oy}StZi-$xx@$Iau73=YH#@3Zt2kM)H_ilr@L+PgX<5&UKoXLOe{I z=7ubtGYPiF(`pIt?if9z?|3}tNE-RQL1B4__Azqe0vQn{_jSqggcTK9-07@?5;UksMO#h;cwY@*afHb|oCkbHTW4YM^j-QwJEKYUtLe9M1YFc5TE*|V zE5-7jyDxl`!()nrJmstKZS&_@F27Cl;;KFtC*2GVqZ()I_%IqFCBHQ`sW+N`zKzf8 z#yNkPXmKJHySFQzp$Zwe`JRI-tK&7y<;3DYJU1dnZz71#qqsI>+<9IMXT}eY{)srZ zfGg0OyiL@hzWVF_gSHrpbl23k1NOQ~Y^}cA{Mj@3E1%hTB_vbNf2K?=F{qq%PnjR! z_Y@#)c{@kqZ~N6iCMGhz$FeVFLhO3iX2la%MEobQ);rIy2ejV4`kc_(po?J0X0VMu z0_jy1`QoSX>)-1r6|<)OasuWB6~dxVE(^h}=2?Mv@mO-B!i{dEX}9RE91```r@74# zWjcfvU$e;zy`2|dJ`*}rJRpM-5Pr-`Z&yVB=Nn1*Q|ukeN%2^X*1c7s4&iHu>JFEU zng7&v?4AGAP5-%bcrf{J+-m2U9KDjT@ZUGi?@>5UWrY8}ZbGdq!BG|tf853P-0(MB zs3X7Sv=ZgE)9i^8Daz%>a%u5cS1oh35RQu$0*?zfe%O2>YuamNKV# zPl-Nys`agv=c5U8j*y>*Jm(rnS~gX=MC&c>iIs@UzlL5mc_i_MN0H(R58VL|HFh5R z#XR1{JdOlA%DZ>^t1Nqh=$@+DsZ3=~h~8;@@Z$PCHvvLf?gdo7UXCa?hsYH(gU1P> zRN>rDb79H)D!g+FWRscm-ald$dhz~7Is}Y1#XO7gm!0qC{CI!Uw|X{Pwmd~PKrYjP zQK;2FF#fE@2WB;6KOH8^(a=4^;@1K_a=6n)o1bvgoVs{K6h3gR{*>0LG-Kn^XSB$w zxYi@FeQU7u%6NYwvIXn(B~`+VL8=D)>LH#aD{$v5G_;LiLfx_0H>I(p_{-cb(%!}T zIGVwkO4&%ctCZn}DnTz%j6jlr^=+Af#@~}n3~rL*&CIQXS9)h|>|_7oGUpYf=hrdk zQ~I2yd*{PI9A0rgR?m%N)YQxBWkqD%PWWR5MS^+BJ7vtMKb+&>nv+oVV zQ;~|pUvV765IbDqm8A}^)@oVe&Z#-t7-vNciD!>K6ztmill|OZW%$!fP~Pf(K5l}- zB|>pOuQ;ck0eU;4QHDKE;T1nwDTU#YQ2J+&i{IK0P6nhPaU}EKkqkXwB)KoBjFa$- z#PJkQ{!P6s^ zL-MAd=U$s1u~sx=W<#z+(VOoM`<};V30y4^&IJkFsHXEOb&mLuFR zUD?P8zDdqyY&FE9c1P~b8?(*zM#E{bNvL;~c$?{pN{SuK6GNCyw_u89A~9^Z_<`Cl zw1_mnHN~o&x#)41C|IaTw2w;Bc#Buj*@G&+Cc(|^?PK#&A-=sc%_MSn73lfgt}Y)I z-ii~ZvFn7Wo|9Xz+F%+KTCUkUI(Uw+v?Q)pB>>~YJBkRZ?as_x#~ zic9vj*={s@pFSVlJAd{H^_i>1)64D6Vy^i(8iY&*R}T}X2`;@BvlG;7l9f8#G8a`7 zdrZ%!*WvLqW+hivcrWX96<_tcPjY#lWAd32iMMPw#~;wht~jFd{eF@2>7riVrBG6@ z=k&%Yi(HGjz(w`bqTI-ztLMkN&I??s73OeieS`0Tk!|{6nri_c1RI|+R`ar}>pf1i zvH9Ys%E!LwJ<9Gf_QhY7x4d)W5$$OBEb-NB7jAaWcFG>I@!O=Lu^k1&dJ>}Y3`;AH2Tm2D_Mum)CM)Eb~C-L|C z@OGc+&Qj5*ez;8>Vthl8hW~z=`r4O!laz4JAmJO5hoXOid9_k%u_XBPCvWi@a$9Q@ zhY4S@OxN;oj*E_%lJ;c#Uc&P>xH}3DPlK{-awt@Oi#x1-sgoULbLGtjk?FJq58?fH z8;-qQ6HiLZL&=RPV4n0}v{NYy1Mi<7Ezr3Yvy>e&b?s4C!3_fID)|qcSj!JCeUWI3 zt76~2h}R5j>oO~vRFfoaK&#y7W!&tWV*I+*q(33{M#`MBR$VYt)a%beQBU-ZZ&dLwYFrDK zkY4D^iqlernmV4%T4!v+lpG+fZ|K*I-(05n3-h(IF-jRZ7O(8xd| z2aN(WO3``LJ3Xx1`)PsYCeQ;Les}X2nRG}7)CgvX~ZzX22I}%BaG0L zVidSk8$ocR8J`h^KAN_TAk6*=)zH*@6mbDfTSgIXXv#8%a6!}fF@y)2ZjK@B(bVt_ z!WB&)zQO3zk7GIwA4iy@aS*===|3wmw5QHbh%+!+h;1K~QH(oBa~rxCvBNYkc47qnpz+cd&7cLqUy)J2dsy&yI)3<8E$rwmiVk2IkK zpo%sxm;vUvQJ`N_h-4OlI5JP%jo23g=7!*n_i6K%D?rl*Dw)NMuYML-+eRN*Gtd3& z{P8M+w;FtZsD}8zY5E%r8P9idVo$4+f{f{_kz6k)||u*8U!t{}F5~Eag*CeyV^}mJsMa zC4e%PfCKp|;6MzDwLnrGjqlXg^rtL;HK4n~HdR-JM&U@BBklivpN@s4cuITk9$Gu= zX%jufxcx78|NC+j3rpmb_KOEc+C?pdWT%G$JzGWx`2;P7@IE4V(SaYOuD26pgAM(y z2xd)6&gF|W0;hjLlRo8~_yt-si=u}LdIz-89@fywr|kNNb3x}nVU~wII;TuM|8PpE z{u6@gIM;ps(6=uLjx6$FJc!`)zcGaf$f$XPZNNv0g(Z2aTe5-w)M+6fppNzv`5E{h z9Q{v#2X%f%Akcytw7_l>Ef9uySN=IKVX-xG02_rGbZ~mHRsB#WB&j0UM}ffe>DkT2SmbUX z2%$S)F}ZF13ew24cjO8PSkQxGL!T2be;r|2{Rgzr6>wOf1xE*n^#NLdIYH3iDq6eh zA1Jel+341r0PH-(Xx40E{JsVt_8bfbWstz+A+9Y<1TtFy-NHRW6(LeW7%|k>fh1u= zSNl`n8J)_|eZnIHZNbxf&q(v$>Wry3m;+`|ZnaLCkdyxF!-xV#1SNmNj4A&c=>7x6 zkw_F;{f1yd4~pPBK=-Nsp@MWUI>_%kf&?1`1+n}>Fk&NUVNi@PjQ{`ZzZ<3RGY3*1 z4Ay|mss5e*nLud_F!G~w`{+bF`tk!9tb(BRPZ{Jw-@YRR(XWB1Am|6;%u!1I_v#-D zOY@XE6(c4j=E z7%pgQ7a;%_kwdF-<#xabA^kldjl=*@^bm-t7LC06r}7)9;Oql{O8&?Oa>R!dLJnxe z?jJ&-4Ax)UK7t2c`417HN8&>izktpL2FYaxfCn0oRKP^Iz$i%m%X>wPyCQVqHzFKP0#2htgcvla0i%SN{s2c#8W<$%54bi$T1QNdIU^Nx z0S}1-5gj0qa0zRSO2aseDAyiFo3jZzxQ>=wu*FE;9w1cV%nlglgA{N$NJ8h`VFZxeArNc2VUQva5xmF~&A7o;e2#2#yphsyCx6V(6G&BfSTOo$ zE=U=MbcK(G95bwt2nCW3;=Oiiywxa-g55RPS*VQw#2W!eBH=HiF>o6ksRJL2#V~x> zNGW(5zK^@6_Ny#gtKX+l!No!JVqFxBpf6k{6#(nnZ^Mf zWfWi-JzUU{coBwa#YNh{drB~jEFMxF&Qy+J?%*L6;Z?Oq3|LwShyx!f1?O-1A8-pF zsRY-5i~$IcX7HW1|AZ{iEdr!2y!pw005kM_4~7Q`6N0ELo*$u5G$GO)&eiju3L%6` z1TsAE`k!TNC&;A)F?8V^19Z?8O5l167mWx*4TNxNsF(r_`8OpPav%X3mVorB zkZN%7$FG3#f~S(AsVpQ#4P2FzW0+cMq$s?b5?Y`~@<4_RaDGUH1}O%IXpRw4bSnAa z>Ga1465^*tiogpI#|R!|$P6cdT4=y7sG$V`WFSw=XrU+=2#$dc$eI{W$oyE~bUC(+ z|5kY-THbvIEf;`B=#Vn-r>qzzniY-4N+~GokXethEiC|3m;PXNls|FchRWAlg*8u|(_`D>5{SW~DA#n^Npbuz7 zQRWz-gtU<$5#I6`Bt;cY3$>$>QN?3~9g<@NRyrye1V;l-iHWt55iD#Ibqq|Z4PeqU zKv6;qJu%$Sg)>MM_&1$n1{WGeBiHm#Ac{;NL*0fLq!i6)nEp?kYYAtB`bz#wix@LV z%Xjnt$)S2{Q2wn{{!_?8E2LSTP?%;$O2CV)Paujcpwx`nq7eoN)O`Y|fCVWD|7dpt z$-V$*hLp&`EV((sDTx1f0DOcfS-^GzW~BeC?ysHUCl3jo3&)-qF-|5}L0EE5$1o|h z=>jK1FMkS1k`2h%FCNSAp%GU&8@g~1L4|BcR(OgtM9B`a`H>BzcKC>~gEP6HK~bob z9jx@Ae+(`MQiQ161&-zH?NDcuM&4ZMNeK`%_K)XCh zK{zr1lfGaacI<`J5i%ET}P0$>C(5Qec8Kq|n>AQb`dn>5{G z5Scf)OG6a0;2JS00DQxXF?yteNLl!=G7NJO&3wLtVFHAZgwS(Au$N3~P9RJ|pqC$Y z$A|*l;K4CN2>oq=Q$TtHUJ-Uh(V@B!FX&}|B1zr^6>ZT7$#sFtezAxkdjwh#|Z6-MAq(}+OfRb$6EN%y-fTLo}RxfPue=gBYK}piyz;8OReCn+)>#1EwpQ4@_4i zA@<3-u#bz@LPDj?*hEkrAyB<{4ve;q=mdOt4y5%S`|5sBq>} zzITzw3bg1XQb1yoAj(DNW0(jEk_4M3j_U+6B#9JR?ksS2KW)uME)f)P+RlKqae`0bQbuF$}*sHZdf79KhmIK>C|D5~NPS z17%>v+6x2rzB}17A=@5<$eOpin*eaEvI! zKY*+3u~oM!@*FH3DpN(WK}xIGbeP3+Yva^_5NjBVVKpQkbVUv1sbuRIQGw@yOD)>r z)^BVaNJJf}4by@s)xnJAse@@2`*TA2;SkK><#8|oPi&l%yLaXAgjNnV4kfyrP(VQ% zV3=gMP^TF<7nJv~aiKa5uuR7Z{)gmhf?2XA{T~2XYJv;<56TlrDJ^jLS`(x*mKFn( zYk_B(Zwwg5PYW3IpTRIp+TiJRObaOj^MabRKw1!-IK+^!HZaEJ#HiGBs zfQ0;XLC>kG#|RDN^$mkz+r?gM&@IILjW=AfkOSp@H9dKrI~<0()EC+mnO$D zDs)OHpj|!SM8E1v#n=F1lp7j>afXzi zfNvRrM`M;dCy=3P5Duv^P_(K!f^+L}s4&O8d*i8me5%8kr8a`$9#!8lW6+k49O2Q&f|bb=Q{K*H3u<Iog<%GM;1ELd7GM;L+ZbeP7i>ReOMpDt#UN>xz?JuJ z46|Vg;@QN4R6Nj|+zPm=#=$T~1h{mVwLw6Qd$L?yCqGsI=M*(ACFJJ;rjykgJTbXY zV`LXr!Q9Z%<5FV|jRb2jl!u5DGIu6mcXXh90y0=3RA!9?uMOC6NuXO-z~EJF0BQii zY`|5~$PS4MU9kb_hI3(DG}?h;*vNxR18v%Xk=^Gx0bdZnrG?Jh0ytIRG)w?3*?_Ce zQ(F*>n8*p)yf_F3c%p!ic0l%C{Dkbf6i7q5&42YK3ayYTb*!KO-;%{J1oq&%6t0M2 zSXFV!AzynCM2_k)f&)FW2j`5i<_Tn42N&})3{zAX4Ns-|mhK5v9|tgR3Y1FWFK ziy-mzH!$$?6p*Q-`d5>2DlDGVV+BH}R~OXvqbHFzXW(-!8zb9t1`{R%VVFY~uKHu1iq6OFifNuk{IIf z0^UhHPkZW9{iQEIkE`ox+qS&Ibp~e_vtSM^js!A?A?I9^YKpqIlpgbXJ==3XUp5ACNn+jYP>mejU5U- zS#_D-G8DtVUPA`Ohe4kd$zWqMjR*A~1{K?zF_SzDjWV*O05T03jx~>AIA*u&Z4{=N zv?q$e>EX6^(zvgb6m8;24A@iaF(~?sK>3fp{VZwI2y7(l|K!9*NYe)u5maxO#*6xU z<6JLxB!V{nE(t90ry-*?ew6$rJhXVMQv>;p5(0h1`T)Oy^kb~X#*5X>|APtb;{+W* zZzsdUy?;S|w`orKCr{!6!luD>5U4EuGL@O28JdceC77l-N)SeX(NoYU9EyA4JV7uA z=V^R|S&lHZc@&DQHkZ?`EI>`{Y1htTlF*H|`AISJY2IiYuXY`c{@|S;z(8pwiQfQf zw*+0PNLkA~kKW5G6-YOs@~tW+`8Nnq_x7HFS}su%u>QcU})V>Fia zTgKr4Br^>?s_5)w?-8fW^$shd5z%`SCyh)qXLQom!cWjZ3M=MN0__SFW^+$o=iaqZurJhVTj4g3ug z<spJ{9HqzD@1>j^c4$Y0ytkiZU3fhJU zBq|3%ZyG#J>&Z0?ndPKz<8+pKG!u0VpT*$99IchlMt+zDO}*wZ{rfD`I(4BV!z?sN zpWhiYn2m`(XeonZD^QkwJ3Vc+Q(2lM7TB^{>mk%vmb$HBrb#?BKVQdS=_b@8c`E9$ zHy))g*u-?ckg=pN*u5Pp?k$4M*;J=8I`3kE_o)~c$#YOfg98d+h<;6v}{BQ{^bX{RIEhvFY;Ewnt*=E)1;=?hTXoO{j!CAbs37HNa?ozpDT zaUmwY^DkBOi$qblIIqlFh%C==u<59T8zs5u460aBHUR=zF66O_Yw1Qk5^Pb@Qa2T| z!m86!2ffZj*Ah_Q=K9amUK^3tC=qE-jm~NQyzShPh*ElcI;Uv~cGi)S{Zw>Y!Z7L* zpkme$Wd06f<_%$|dA=Nj36*pnygDEAJJe6A#B}oSu)kI)gR5aWe_kXuTLhU$VNADc zqI0JeHQAa)rJd^!(T#4J>>41@2@C}zG~4!udgGH5kkXQPxgsMNwqI`stL z70UwqCh2@xpvnrE++hmSuczyab!F1A1B#WL7O?+PWBhDM1GIk@ z(?kEjviEN+G(^z=?sT-N&4>44AB14@bDTEkt`48$)?#8Te%YDP(T24c_xJJ?+9b>h zm-4Uz5o(dun~R?O(8)cn_gLWII;j2OAp^hlh+8pF1^8OJ`-0t^u^!W%*E<1hw7(Gg zs%(JIMi(*@Bx$8GP6RN7lk-Mx^9*(c4d^ zaH_Bsxd(Tld0XLhOE>ZBPkVd7uA*_*qK}hZnLSv^5YY5<3Vh$A4>Kt#V)DlRN0f1? zKaz`%ID)sKpyoe|G{l18dM)+chDlI6L}74GBN86ECDjDwSl zR`wJBgy55LoVMpre6oHM!$7kg0lPXb4G9&Or|B)!e>=>aKAo8@+oANY84QNS>piL9 zCD=`!uzM$JKWQ_A&=i#R_C0R(*aKbab|;6|#TOJ&K#yHwb+VlS?iX9Q z$K~vT+PvLNPv58arNG^&ZI}Jbd`!a-873GjZWyIveY!tGUoye;$*SPLoC;f?p$M6& z(jIiVPPmICvK1ajr-|PKMLUl%bAAsND}zrk@XOLWwy@n{tW+|K>4a1`oBk2tYw6ut zCf8krD*I`0-@TBnhVL|@gcW-sYrCre17$y858|K>_eUg;d{tWaeF#2#Uoo?JANqRW zTLEO!??-3ApW3&BuKQu+|6IuBAX2Oc5IR%$qnH(L3e!lsZBT%gMjXIVx|dZj*a3SP z9A9p3AAkWPvA;NI>n?4@)Y^U5f{T1roPmmCWHJ#2t)VN(Zl7s zD&}|tgM~UA!V%+TDt!pSWyvAL))S2tkq9ZK8H44AahTTrF#2E5RtnQfy5EL@lz|Cn zPzMG+ondfMD43K1tN;6o(^4}qS0#02;Fk$t>BV4dCdwZ8J%dx3sGN5{1}lad^b~po z*1sIc%!DIYw_R80hg|=uUnMn8`ne39-d7%pOY@tC$YUVV?ce zE%g|btw~bSno8r>DFF8qk3)U`P0VaLjxFF9TLl;(J>4OCg&!^6WAGCn(<)2b_AvA9 zeuEE(oHu_%c_-`_gkaSZs7+QngDuD4zSvBIffk)WR?QKnb5FpBdB+qP12sK~kMMI& zGBfui+M03{P@Ha_gwh`8nQ3qed(gMoFo@y+^t36@U=)WRj(Bw76zus8TLvNU^b~^p zz1t3D_fZS`>}ZdNwH`aQ*A85x5LvoEM$Pu0hQVDPGgDY#D8c7l6|jz}IkpJbG?SVd;^B_&k%Qd5eC&K6nf#!2X>}O7 z*x%iX_Y(YXO`M-!k%WQP{$s1}8WG^29tOEv$a)5P;!4}85N_@t;p!XiPSuu6B`K|jdujfF^7LP*iKt=ceW}7(Texc# zcOxAz8_V&HQF{~3J_|1yP2`e`i)vZt(9I88jXDZ;m92D3q{ZQkMM*1r4g>iCVxhvs zoV3D!Vr8XKi^@Ym%sM)i>Hh9Id(T|1A`dSlI` zFqZO0+{7yd+wN9%%GWo9rA%Q)Us`?vT`MV+nK>Pd8fq7A^rE4mIA*n1+WjIb7FC@E z8ec@LNXGe#D8(+l_#&pcEF20eOu4MxXmq2_*Dy(6->PEfZZ~@Jsovk$kSk@oDy`RUqYuf~QPUQ?Rdm1Wn17G%RTy{5 z5;B``Op=QzFz5!FBIpKcdg+|PL`Vm5T%sgr-$1C|c1dB}Df}i}d=ZgK$c(!QFRVuR z5g?w=amjauEpA^0hTCm|et3obkPp20u2(8bDG>CkO-x)WZeK#IH# zL+g7g4DO-bM!COu38u3&1(!5#W7R+B4kqh{ci^kb=o1d6wxq$G3<2)kf!-#;0{Bt> zU7LxT--T@bP!*FOW-{`b!rr^^YkS<%a7af;CF(FpX<{-_=X>zfs(Q>M-NQ1VenUG* zyl-nS=^81bI8G%3>`4FmF4pV3=_nb8kVQa<+rU#6I^t~{&X3`U!DLoZwAEPPf5iV!feuM_B zIiA78IB2~409|wEBgnYmO~E7V{kGyVg)pJZRFj!D)@(K3(Z}R=DQ%WHNa&HQHx&NO*(q8*<|6BS<-o|2rF$hsW+x; zH>pG?6rd-jC99Yr+e{wxxBxo$Y*lFcTRB|mz?BP8%E$eXu|Kqc&jY1ndzl`3(Bw<` zPmnb+jhToHlb8Lfy1i{)WjNJhR63P@g}xb>X~JFBr^q%iQ(;ULbPU=CKZA=)K7*@L zj;hkSJwp)AIHqFKo?+qWbwb4iKF2vz!YLKgItPBSYh3>v8WZpV)=|EZ?mtI&tenS8 z%@>$$3LN0^3mmW|-8A{p$t$0F*`623Z@t0N5U48^yU8H(B^Fd|ZZnwk5+-!LYX^xB z(K7bP==KVkA3qmtPwC5d6!!}IpBL}NZ+ZIg%GTUv4aL5)RiOT_F@op0&`OPro8yIO z>&({}hOJ#y%m|JVA1aJ|^+pH1$dxyZoN=}6iD9@rP?`>|0?+|ikR4O8z|@5IBm(qvqjp2+ML7ulV*PBnXw#YM*ZtSJg@q+Tv^Eh%A|!Zenq%us+k)rp6ZK@xH; zou#6ON^)aqbG*VBXiZ(59^R8s>d8e+`@70@ByZdi61{V# zjI}r_QD>8qtfK+N<(g8*6lV4mM{!?mW6;}8cB79w(8K)Qpkm5Sg{~`YPi4^U09tEU zA!5UMH<)y8FVisx%~(PRy0!*%(0--|XyjThhp3}Q_9KfHzRJ|d)ufH-BDE}a&oui| zNWrJx-b5?gTn$Bo7qoJ?bTmf*KN@n@Y@{$9?A!S-7t;L#mfhS{5b6ZC)ARP?f2pzjO%@C_AR z%OFQcp0|sbL?hl)EH$8V)9!x8HhPFSQD}e)&j+6+b#h0B$&Wr`lLcEl--)d!r95#W zbky&K*~h-hu}ApnMpSgyGbb4>oiM_4Ctfjo)g)`l-y}y$_1~$O7?b>kH1WN{;9|0# zu9rgBLIxcLnk+Jp{@!LeP`YMR(zLX~EVq_go1Ga0d0XU0Qi4TAkF>}wrCcjB_O~Zd z9x!IQCrWu|f#vvn>h>aw(i&Oi>QY&s&*?>0)M$AbXWB^LRzbtsDxZka`|3i zFa}E?F7^9SVem+_uL6uXqk*z0UkrreKQoO-M|c|HCzqmhU%7$gKj?G1U?{R+No1uT zOQQT`gFhEIQW9P5@bJ&+)_xeDaU-4SC}}75Ji_(%atDmJ;1Y`s<}8g-(erK47!a#s zUfW<>Fw5 zSzt*ZOvYiAJ^zPvi!rejvWKQI(W;bOU#fpdfQnR*X;FXp)f{zFIOVXA>LX=mh~G*y zC`fLIKMHV7k}8gSi#aFPA-G@US8pDdw2~B`LC!+)S$W zQURW{wGui|!E1%_Apc-Ed>~#Rg^20Y%j!mhg5kXJdKD95vYIJ67=HT3VpT_ubM7js zz{(iA{VWROEwVTc7HuV*@-6aIq}(XGG9qO6ZYoCK)9O#{Lg2U>y;bzJAJ`1X-f(9K z+HB_cLZGk9Hci(5I7sJ z5OIMd*6K}5!(e&RM1^iAMg2ze!eK<)a5Tv383GKE%FQO1YI09$-yG^wP3|Z8&SRmh z1X!B2(CR^ZEn-bx9W!KE+_w`7kmgCfszd(@T)GoXn?>-IeRZEL1drkym9Pfy9X)Bn z5fC^7KAMSWD4qurIb2ia2q=nby<4wd8QulUY{ke#RPDqC*=u Z{K<@B#d2J8Ts!~lQmoB!{IR5B{|5%|5TF16 diff --git a/src/org/usfirst/frc/team3316/robot/Robot.java b/src/org/usfirst/frc/team3316/robot/Robot.java index 18396d4..9ac69ab 100644 --- a/src/org/usfirst/frc/team3316/robot/Robot.java +++ b/src/org/usfirst/frc/team3316/robot/Robot.java @@ -61,7 +61,6 @@ public void robotInit() { logger = new DBugLogger(); config = new Config(); - timer = new Timer(); /* * Human IO (that does not require subsystems) @@ -87,6 +86,13 @@ public void robotInit() */ joysticks.initButtons(); sdb = new SDB(); + + /* + * Timer + */ + timer = new Timer(); + chassis.timerInit(); + sdb.timerInit(); } public void disabledPeriodic() { diff --git a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java index 32b0b0d..afb1f63 100644 --- a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java +++ b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java @@ -29,6 +29,10 @@ public class SDB */ private class UpdateSDBTask extends TimerTask { + public UpdateSDBTask () + { + logger.info("Created UpdateSDBTask"); + } public void run () { put ("Current Heading", Robot.chassis.getHeading()); @@ -59,6 +63,8 @@ public void run () put ("Integrator X", Robot.chassis.navigationIntegrator.getX()); put ("Integrator Y", Robot.chassis.navigationIntegrator.getY()); put ("Integrator Heading", Robot.chassis.navigationIntegrator.getHeading()); + + logger.info("Finished UpdateSDBTask run"); } private void put (String name, double d) @@ -93,7 +99,10 @@ public SDB () initSDB(); logger.info("Finished initSDB()"); - + } + + public void timerInit () + { updateSDBTask = new UpdateSDBTask(); Robot.timer.schedule(updateSDBTask, 0, 20); } diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/Chassis.java b/src/org/usfirst/frc/team3316/robot/subsystems/Chassis.java index dac1182..ec970f5 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/Chassis.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/Chassis.java @@ -224,7 +224,10 @@ public Chassis () { logger.severe(e); } - + } + + public void timerInit () + { navigationTask = new NavigationTask(); Robot.timer.schedule(navigationTask, 0, 10); } diff --git a/sysProps.xml b/sysProps.xml index 100bd8de065083577e639f84dfbc02bc530afc02..7e50551909ce9e8fcdbcc4acd632d760796086e9 100644 GIT binary patch delta 20 bcmdm|w@+`w0YPRn28+pog5I0?gbY{#O$!DS delta 34 mcmdm|w@+`w0YP3<1`{CEV=w^0$^IPHlM{qlHuDG>u>t^~atHYU From ae2062827359d1184c47df142bc64ca5fae26270 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Mon, 16 Feb 2015 16:37:13 +0200 Subject: [PATCH 14/29] Fixed bug --- dist/FRCUserProgram.jar | Bin 1783355 -> 1783351 bytes .../frc/team3316/robot/humanIO/SDB.java | 2 +- .../team3316/robot/subsystems/Chassis.java | 2 ++ sysProps.xml | Bin 5950 -> 5950 bytes 4 files changed, 3 insertions(+), 1 deletion(-) diff --git a/dist/FRCUserProgram.jar b/dist/FRCUserProgram.jar index 90a8d36f80be2bf29a8b079598752f5b8c40a532..b6cc4a475de6072af137120fd8ad89987f6e6b3e 100644 GIT binary patch delta 25389 zcmZWw2|SeD_cxDihQZj)Gu9AUvJXJrD&0qQnabGsI(B; z7okuoLK`jgKhIpvJAVK7^FCeYd(J)g+;h)8cX^(<)E#}kJDTY^Lr_ReK!7eFAdr^B z97hbL=2$%@1k!RPXzEm9MAM^+0GbgL6&bXA8dd5FmT=35LW{Yjwa7hgDNIk~mdT8h zl2kQgB{NEVvC=vzs_f9&%B0{}b1rZ#B*Fa)jpM5 z(jDu$7zTh?5Gd7@!DgTMJ1?K%GR62 zEfy9KP|eLgJtfJvD_(ZC++VkVeAnH1G72;=K_A_5rW?mxa@^Z!u2iUXM4@@N)}xRh zQ`xYw23y~5_`T_Z{@arm#6<%#)&6`Cy?XyZdw+|SYryn|V{a0cfBD?o65qS@^QGR` zR$revT>VQ65*#mjTJpEEU)GQlvn@GeC7sQ@H$mwpOO+n1wAneSV};-C)aXRrw9WnL z8B^z4%WT+mB18F7=i(0rQ$ysQAG;I0DdW%y<=o&iD_l3-azB@0dcQVgg28;Y>iw-5 z?FJrqCfxn9Govj3?Y`Tm{#a`(+l_lLS}u}ck0Ovv0^L7S*{O z*zehC#k&ihY1g^3^QupI-~0HWFwf$yjQb1gdgX`8sozUaZ;{>ExV(Jdvxx;0L@Wk& z3u#Bpt&%mfc=jY>b(D&0Wvk=lsECz%3fooo&0BQwt*hVj9Gg;=XFjtk#3FAetzaH6 zHypqGeC3Wi--;s`-us99yHazN4cOm2+*oCLGv z6=E$n5``}{Y8J)asMnRV6JFY0AkZ>9sZaI6jNNngx-lnx+4L#G*L_Z(y*<6nMOf|h zjDW1!CA;%w*$>@p!xE0lt*!fUYgSLrYv0Ust;^)+1&L}O$x6tneAl_v#%@4%UdPUo zX@(IGLKeQ8HE*Y}l~ZRHQ)#t(R*1Wj`H?oW{oz~YeBEk%U_-;6OL5J+f6VzV9PmCP zU{O-#*wqZ}D_358V`dX$M{?ce!mEQi~($pziUTrID`s+Te zXUWTr8$M6-bC|X0XJ+K(^WM`K(+V1AFJ)Tf1#f@8GHL(O2#L=bKiEo-CQhe!Y+b3* zx30-Y}~HpS6?^&3kvzFfJr#zw-2p(N(uRBhByWnq<#>_G^2l{oGPT=N|j) z@{Z6&J(-2O8V@J6erVo(uzID#xy*n^!yCe~I5L96sZmnjYhI3>TdJ`_XV0JY#j6&R zpJN?Lj}-g5_(!d-PpUqmVkMRz_WbFjS-FX=mG6dsWrh4+IkR%yy1!DgXH^U%o-1zt zQ2Fua*3}22OYBWF9^Fx${d&i{gv5Ho&?WVEkF$N-Eq1x9UNIdSNSg4PleXnR)dt5? zOZHZUYB;M|ed>~(9vRg>N2zFT_6NIjIk(*o_e>ESN=|Hg(5gPUwy`l$e*2qZuez$4 z??j@DPs?vNAMe7tFMV4qTEk6)5UcTRuKo5rrNI7(+|=CNmsBOJ0-b{7z9?;Iiv1uK zn&m8gp;OF%s>#$g%Qt3o+LFqzeHGeo^hYrxIM{sc-fP>078oo<^tG4z0`>m%vIgB# zdSxbz=`&41;+LJdh8(=6jx&8vC2h3UNTlT782p$!^iejK}a?^+4Epq=veNmSa$w zTCc9?vM8A~ch=3S_$g1*f`XrRtUNJ))?6u8)aofu?JfkC7f<@Opj5Zysf14hEm|`% zzq-;$W6M0N@+HpA$&EU1pA;zfp8Z$y8M8eo=+^DhEm6)ZonjA7Ipkb^ zBl6~QKSj^(;LWdTQ}Wn0X5#tgZVxS=XkFP`d~C@M)noa$E1T{(Ylrm~53Fk)FdCA5 zxW08yr(ZLDrNe=Ofy4vw|L?@s_v<>J+&2=qApF<&wCJHD6EbCwq;F|h)~r!z8`6C2 zVA7-$xBA@K@yB#;m28cF6T==TX}qbmX^s5lfLm+&7O)47m0bHR^wafvr;o{oz$06K z_a|=^?O(6aEvRRoE_H0s*nUj=AwA#rMH@c3nA)FQD509y&ybJmPj_7J9Ukj{`>0QI znwRhah4w>YsKuO3+wQJWnbV4uH9V9&#{;qc}a zGml?guW)<7-^FdwxefFxGKQetD->bS(Lxq{cw*Ysqduw(I8!o$B{bU zeBym;49?u)7HE0RUT4!qUz2Bk*t54e-o6khA$!8?<@2QpuUC9IGRE6Z zpYwLp9HVyA`R8iCD3`_seO_L3Vw~{opDV>5s1zMG*innhZueB?8vn?@p|!DO`@-B! zspGaEM~m=+iIhz`m=PCZ)LLrrtJriPl>KN{b{~Yo$W|c-Ca~En;+0p`8^yuJ51ezC9A&ZvZ*HC5}^VMMLeXFr`aZp~wfffw%2zcu$|7nuL9OB)~QTyvmbk@0D7 zl}*j*OuPQrHB-Y9;-jK!i!OJFr#C;*^Q;N%w~|PzEl*PspP7Gr=YR@MHqKYnFHsK8mxO^Y^HL|lp8 zG$-#Stu|J|L+i7{q{N}zslIuG;duuiWr}amOsGiXsMzi@-S$u(O`0Z>RN(B2~NA=S_RQQ0q}sQ?MDyl9|5eO6|eVteOKIi7%r*xto%T zkDfo?DQeOCV)y4RnK3y}|0uuwuA#}cI&rvlae8RmyIViJFQ>R2Z&<(m)n4U8Ikzgs z7EV3gnq)AuwX6D(jd1Dud#z@=3ns>F5MAZp?4+-`B7Shm)8U~FQ9TRY*$X~hj@CYL zKg_4va*{@(B`t4q=~r{j88Y2xB%c>|_Ka;kIBiDUeIH+;m4a1=bS4Hj$vo)i=E$AY-bTrt-?@Zi_GBr0gnvIqRf~ZO&&~+7|A1+HqyN?+bBF zhf|sx=4c#Cke+h#+qGT0FUROLMeM%Sabj=nX=|%lL(0D<%Dj81zh9*=Vfo~fT5_cq zM5M%Qf^J1WH7h9SwRL$M(cGu`Zq14))hmIAE-e38YH)P;=Yy^Nt|D^%4VHJ4PMx0h z_Ppaa#_*jV^zOE`gGp|>W9x2jZFOJxd8&p+(46`Shx51TD!FKEK4>EMZ05nkVai{W zcDnAA@zyC1ks*srotw)m-^qx%JPYw$e?6?_R3KD|comr#TuPrVHZRH7e@iEOo~`Ec zaZ3bdp0VAuOKIP&)lbZ$78uc@y1cx%p`QC4voC9;$}c&~zFfV|C0ImXr#v#iYkv55 zwoi1)I>vFc3o*pA1C!(Chu5>ygks!8-sIY!IWxZU2QyEs<0Ug@_qFZ!x4AE}eWAzs zXj)>Ub=hpo-VdkZioUZa=^7--l)l@1+(N_Te)5_74GU|YxPB^j-S*%-!+S&1jjz>P z7TpOt)Vn0esI~W6dcylh<8;c2__wQ@H~KekufL#p>F14Vl>w7KM?dTqRg$*v`k8q( zZS$SZ;EZWULZdIW}4R*y~xGNxhA@^^LqXM2JVo%GwrU@2CbU6k8c|%ZZ&vbx2N1o z+P=Q+U0AV;YDjH+g>zYm1^r=jXY1Yv#eWA~rS|0))b6D(`B7w;7Smr;mUixEBmC1) zwAWvvXZOtq`;WAj9B`~Tv4Q?N&#ApADZlY#P=bqbx8$bcpm2qnnIA2S_O?5oq&%U0WW?^mHf#9!MR z;i=kQcP^*r%%PceIz25+i_b>0yni{2-h4E2woMr)Bp@Kh5D=JD!M?VddnDE0XM$oo z*^JzVo79=I;>ArN?isW7mKgUq{pn7r@W@#+?>$>g3|}>HPtnZ}u28Isy^ptxP$GJ- zTq!c{)m84H)w0E#BDc1D<{n2^zq!sW?K+-uYbkuZ#id_&Kj)U`dpoHTj`x$PYMo!! zbK771;{q2}`$-+=D?)x|bItqlE1z3y$51X+!ZCj)6lddTN)&lMi=c71f1D7av8aBY zucp(kQ3}r|GigcOKWHr41MVM9vLm%V$+)pRRY)yz0O=AgGw;+EvC^pa$;K|=cao;3}hTcWMp z9z9&Y$1Lpg&-Zn8dsc-0*l!hcN$}colh&-W0!U+V1&nvLfDOK=$3| z(9cKfhBD;;G-s_TKXCN-o=fPi(eCE=E@P5^_s=j=r3Xo?etTOapn6+#!5_V3b=Adn zr{>;Tq&nd*L7SMVb9vBBz%Xj;xpn?`6Z+$ghBZ9nw%Q!5ojt=t zdyUTuPsgsAV=WHZ73CL)iamaJHGZt2VN8kdJ(g}(@s4$?=LJP*ExzdzQQ=`VQ~z;T z(j=F>V#%}T&Q)&A@L76K%v#)~=STUD>@7YMPv&f0oU2i=v8d0rE8%7+WBx7! zD|dG-_&Vm%!%cObYaFbP>=m!QG}AvScXC1ZgfXuZ-6~UcioVY^B(_T%=1I<A{o8n_^*3FNeCQO_=;_dn7xo+65p?vaDZh!r{b;VOki;vw+uqh$~Dktfc z1}HKfD^5!~EWdN>t{#<7RhMipHP{|9YkuV9d#lpkqM-c7CVS^nkKN|71)2vllu7Sg z6SELOYwbB*uCM(yJzrKPh~GL>V5#+J%xZ62ZM(;geoIn-V9K`@1m-iRt#1?!E z8Ti#yVp%uUs62G~vxUL5{n2_Azv8}JjQcolTHC#t8QUe3V!Ssm;q)9IW~t;Jk&2k2 zb8-5~^4egX^*!zr@2vYh?cUxSZ~ER=+(}C-P*tt5{{E$8;%CQs6*l`8Rk}>kv3FCA z@+h5A@lZrqJ*Y}ym&Hcw^64?Nt(N-8yKzLi>I{$X+z`Fo=h2i;VqXuvaSXPfT-;P! z9^=37gZpxic-N3$50YZHoEdi_yRJG_veeXeS9WRlMD!(kvU#cYgO&XO)@v4>erxpZ zuG`WlQ8&V58|RmDm`ijm4$8OAah0m|nNiWJHd(jvXjZ1JqK)0sB;U4*FQO$oW)xp6 zzj$$OVMwL5QADt7L-2))<^6|^+*V~Ru0JUe@H)4%{#$cF?1W3Ns`HXE&UM78G*q3* zwQM=kQ{F6gY4(}2*T*WQpICnQ*Q?D!RD{2cIJg<04H$gr?e&5{=hnWu+ej#%!_WVJ2 zt!FL>JG1@n-`)G}cSv0B(iUB&n)F~!n)>g_j9l+;t0(UnGx6ZQ@#>dUrZ*l}6+8Oy zoAS6D+hz#+s@xUqlDD5cIN33%CnqmS?0ku5W9lRMqV(yfO1y8Hn-th=JC>I_USX-_ z%JpLwu3F+{oOXCjXnLgZftqqcV%-9-LqVeBXR+RY?G1A+8}sqzOySEF``>qW?DoZvF6mfgbOWsdC|IZ{I;Ua2NO$`Qmjpt_j;Q*4EReQHM6}l zXSLQlg}*Pg*Homg8~g3@+XJsE)-^j_T~Qkr>G~+?N6}BuMNfLvb-iaC-E`;u!`1P* zer5}FKP~J@h&X36e$Tzv#j0Z-JX!BGOY5)C$^a30Ej^{grgtqg!^mX=WJPO^VdR)H zxBYa{KU)jkZ$F-5o?2ef9PsXv(dXHcr&z4UMe%c2&QN(0F~cKmwcn&X4}F%`b&Eqo zE6)!uur!w+lhhrk!?8N^l>L|`e=h2JG2>pu5C40+&dse=eb_6RvS{pIniK7?;H%OF z;qgfv-E~s_Pr9znlTg$)tFJ22Eb7+yoUt<}ec916^2Pen-MjsdPme5vt(9}O4G=*$ggT+bum$J^g|9{gRKeSCTWjoyV04#E7*p17oHB zu!X`)?l>}h7kl14ywlaSZr_xvUsu@jCUmj!t2dSo)qsivFP1c-EAZ(AT#s+jra`8q%IO}Cjh$LmV( z(5u}Z+#hr1uh_iJpPDAADs@~}cr5)o%d~rn@Q*?={-A1nlk4kk+83mjTu_VZ7qEQm zWK*Z$Zh|$zpeB zlw7|*zTm8Nfo<%T$B9-G`yM`@k(Z?EQ58vUsg!8hDm&e2-s{1Lp@m~~-W6BWdc3du z!kVA6w_!!Y{g^v*6PUsZk2Uk&$e-z(oqu(c!bg#3-UIP^-`Bm*JslmF?VG*$VdT42 z-V4R|t}$A6#B#v??L@63!&82(B;O1MsPwFVtkkm1di$=X%-aENJ>i#^tu0KGntdZH ziS){`jVJCI9@jNjD?cx{(-66S7c>nqOI_r5F(>X+pAaW3@!+=hl}TSjz3Sg>^G}$h zqBqIzW6Ae>mn_WQKb^VuPD@QHd$7F6S9s`e`pQp-tj{|iMg{K+^WMEKf8=HmTTr1B z|3FP&Z2UMOBLlJOiJ}X}UbiRK+%7L=UA?(6X`r)D&1kEU{)VOFw*H;uwKh?DZGhJw zdD$0Nt5{cyb%%3hUnB`sU(p?&#r@-u?(ie)wa0J%E=XIjBC%-0todSptc4HknReY) z$}@H~Tpiuo<$XQUfBqPGgQE8dJrcrV=PsViazHQF&zr2BbE@HqY^nd8lG1^~(&>Y> znLbHpXFNS4;odXh?rhta%3hadtURbGc4?Bnm_DDo^yj?f8?dVyRLhoC;G~(N;s^LEZ=Hp9mt*)pzrqEmUi_|qg znYHTk4dz0dQ&kG<6>i$@9XzZYMe5qKG<6jZeG8qRl(G7>iug@QW&KrEW1gl*b$<+W zkL%lZb61FAqRRIpyB@8(U>W8*ZGT#r^py-@c1mJ|F^kY$G8qk*NbzKQHxcvMb4GBVmK=kV6s^(*W1OO{M` z`J={vEI1!)MC+&aMH_RN43mj7xb6 zP5|QaQ`{5fXYAz^o&Aixj4H3c10l8NY%7Y`_8Ewk&#}ACJ!gkepxO)eN~+xTf}Kc} zte2SH^pd@Xq6J^Ew^C)+D|Q-H$~WV3Z!^YqUSqm!q%>>6dQP@r3p85UOQ?F;t?VeO z9BRd5;NOPn+BPg_^M)Nm@l86x$lGt&mJ~5O0>-?>-Q#xW<6GPv&31M)C6v?7UO4&% zWnKq6P<`a0{M;NkWKNM05HN=K+W-DLoMLl6H|6NK+=BBANzWNHLQar+^GzK`(bW#N zGSPaKVk41G_PBpW5s^1@``2kur(9XCa?6%Irsbe<7@i6LG(&kf z!zbt#QF)8f0Jt{tc*kZ^_QScg8PeMSza#XXYdE)XY8pJ6*tKWm3*vJ3rx&EHbrWnl>94S8+6T54RloED)E94|zzKO>xG~8tzyi70L=@hId$N`SJ>F1) z6VcNyHuat!byJ{B2N%rU(jkc)`bpfq;ta7LFpmTXu)t-M1)sXGj>{j}@@mxRURmfq zb18_LgQ(jm(KD#;BYPgzkUPv0BBPh8>4eHYu{9`=nmWXaFG!k28-rNgY@d`;%WZ;&+vI^izFZj`vq53XiPJh$+N9AAKe z*vQa+8>D2$8H^4-&nc-lNC|s*l@GJ`e@55(C$~o4XEp;J>A}9e*aIE8|LY$^jq02R z%yJ@Zh>PXkACgDwKI74$ra$rLFU2rLuSUQw00pND&`=JOW`eAHal)M23up*2f*ylA zB1-c;3QZB>q7#vJAGX1|571mX7qv$c44OE)dzs`0-zkbUo5^KO)BoSDp6Y6z6$SoQ zg=sf+lmnk4r+%E|_Vj~>V%ZTxy878Flp*vlfL@ayK@AmX3Ml3ao5@Z5YQNYV!8S!2 zN-?78|GzeGCC!X(0oSg8F}5DnrY`FL!k$KHxBUv*=X0N@R~f1B_bXeME6cmt;Rpy=jgpPh`cJtiTKx?>GV>d>8)U>~*`pb~c+`GU z=q!to3I{A`63FvATaUIKt@+NLC|EU-hTupr0et~bP|A)=O+kx)fXH%`{ex{HzSE8- zus9^nC_Xj<^$)OB&^%32l2(NVf3R(dcXp`hFIx$@4Y2hH(w-v5q5~8$k4tEyz5%uY zaR3u}muU<%a}c;)Bi!T%U{EQASUFIYwex<1h|o^}QZRr5MF|F4Kq2=>5SAkZN!3rb zE+Oy8t%QsfNm0c51v2w7lBWtlI0YQx0!pZF5h02y01<3+bgrWQ)<%vraxvkUz$4U=F^g0{<5FoX2sZrR z;S|MGEHE#XHWpRU!Q4cGBnh)L3|A4PE8(;W6MBN=RHAz`CYrNpkY&@s@qT_J69tKo zLTGH(DBW^de4;EN(w0EkJVXg?6(aQrlLCyq5`u;V4q#%2Ff??q5EB=LNq@rP5GHIy z$Vo)T5lkErA?*o;lUxEKiH$TxNh>11>OUY~lyo32UBUpJ^dS~k|6{75d^$Ou7<2s} zpo*>y!Z;c+z^Yp{ToffU$l1isyZ=NONLUO!Z2Mq@`v80v^p?#;g<_;Cak_yAOQ7l| zni!I3gkUxn1*fvb!Ku+rqXksZ6*=JTq`FL-|$teV*m5XrW-;W8+)^z*>q);Oh zy8gHm*HM=w*~nc2`mWZ;hpg)Z6B;C-J7>Q0U>{=sAdeX7@>NNYx%3OeEGcp>@%lF= zvZcUhnF1(BhSWu;Bw(CL7CD6`jDlHY7y&a17~@egouKDQL-VF|9-x5MNrTov289@* zlMF%@?Po!6e@jDe+r%l@0?m{mU1(t_TZW7xhFBD4gREphle8=*N@YnC!dxD`Q3M0r zl?Z)gEJvCWB1$~OgmR)D@t5QwB+{2BjR|oT9wLI=RS7yeF9-2|Odi@7P#w*aM{8(c zo00NCbQ^#~7BTa%Pg-I9@noLMzQ_DFJ z(buP9SYjH$63QTWcseyMIw(k)bRvS>c!V%&0E7nn8Wl2>F!#ocLKSdPrSE@Id2l1%0=A1WIiHq66{e^V{-M3We+z4p#$x7hq+7If ziBU`hlGY(dmeRQ>N)wXh#&F!!HBE^4>mvkHiyTk<93dJNICL~m3!1S&8rqNq3bn`y zw0Qh?pDITP{h*kqD8QB0MHM9a8_p6#S=um|x{@Oi_srSmcY|=#U}A z>ZKHBLV1CXl67I-nj1SB5kdpHq#?0o1%_X)Ams3(yk;EuK6E7y7DErmk%qL8JUwy- zVYe31^q}|3$uP-d^dQ39lX!?6I#31!^jZ%TeB6j(8GW!Ye>)~ZC_;Y+CeBfWYaS-( z24H&$axx(25Ul+ebKMWKC<^wYh-CvS-g5&`yQ~QFBn(L#BH{=p7E*-oF-*jcCmHCP zARFwpRMf`w+(f%X04p_%AQd^{r~7@;@Sd`P+xX->4> z;31+&t%eXoq%+hXG=lm`_xN~M?*Y%=7zS0X0mJtm0kYi~yqEKche)F?N=D`-M#h^! zT>fq05#lJzgfyYqq3b53H*v3fgkeffB&PLYBK8}^N`@&o!|EFk;df!_0KvcC+Kn{K zNI$}32n(kVLF%csfIgfxgDLh4HJZVaY$%MH%t&PvAuK3~qW{2XBCXK=HN9|c|K&W1uU&)BoC29b-Q8RNKhT6J5-e?AW!*- zg-k8M$6jN2uozly2`TBTE+6v1k~AZ#4fqfpE7+k#oAV*%=7O^5fE5@jKYpOx4 zOJP4s4FL!;&{ju?ws$vq2pbJKLapt0cnAYE-T`IxdeCIJ6AYmoY$JK~fhU5>oFI>U zeTm^9XHpD_J43E9Xy+l0G4^2tzn9Ua4tgMz~7#AMQ(=7Qc#hDg1`;$zI20-NH6@_b04ypS}y zHwFCHuY_T#sc>EhQpQBgRMMGdgHBI{KzyNzF_meMt5)h@qD)6f9%bG8*O5K2eT|)LRVNvVki8E>QfRL*!88SyC1!vX<$f@PixXMf(cT5oZS2>FhlkVWKQ=FeG~hXfpHV@nk3;u+YE^ zP_lO}h7D%IhE03{CO(D=$)de8A=RG_m4`G0?bFNRu*=h1SH48nTEuo`5Ji z76*#BQqSC=vH6L7yn;j_Hjdhf?!X(H%*RV`hpbn&kq_zF2pxg7YGhsgN>vfh;1e+N zfVn+oCm*uOgS4T6|2)VbqP&QY(N`oSj@&(=H|)tUbYn z^U8!|@QNE&KC0KV%W<{La_AIy%pZDzg>ID?zUB>cF1u2QiB!Bn+wcV*EQ{j2!Oy{0 zc*rDT;&n`@%_8lHv$rsj>;oBU%`DP|u)ohkgi*^ZsC}o24;k+Rp|#{04{@MfM%R4E zAX+HWm`yGuIy)$q4mvR#a*a+GMQ9>%U(%5n*Mo^zUzj*szG9;8s}KXV`GVDD0~qNW zfLY`?2M~kb7|EIgs$LFb;`1D6e}NEk3Wtg7=m)A4>6q}O3oGCer^^cSPxBu#JONl! zWQCSoK8odAp#l?FB@r4E&7m&uZ_lOnon?nD`q4G3FTp9=^Dr4>=J6u`hXuhu9JsM={~Mn4CsLpTI=bVoJGR#HR)U5$o)=ddCVkw$7uz?x!`hp3_K zCE%evO^h^Xim0LL3Q#5#1Iir7@?gl`F|ZffZiJEjF<{eUGfYUBizp)2QqZG40V4}0 zh{)k|leiT0*iXdp$)zxLOB^sE6bt&6xnQEyMMN5f$AXG6Q!!E&3+wvZ=@h|1G0Wge zOl%n}GoBti#D&nAg^35tNH^l6FOMUdw*n?)eF+48@N#HBVE+HGjxUGXuVdk(P&;B^ z>3;ySjunwb;c{?8mAnG7scAgLQ${iIB5YLV3LeT&6yYDV^t_cYX0RB8m?{cM79sHl z@We_m;0nAgUI~%(D-HY`6bH41H;eEm@~@k)dZW$YI1tbyI<{a$eXEELYM_wQaIU6I z0EB_mSHZRJh8&Dk=ZMHtMvWw)6RV)f!d%R2&V_z(d2LTfVMLE7*+lm)loJoPgnsd` z4Npbc@nkf?+Dl<7$Zapg(|@|ACV;M!1(=td0Gqz~MLa?jeN2Fv{PQr?6p0)YVGgc@ zlQ~74JSHN8jwgcMzu;s}#c^LEwV8%PIYk(p7U4f&%AFnM4&p49vOSBXSV-sMC;|D4 zSit=v^c;4`dc@kR$ZIVec22H=8-bfwA)NlZOsKjws&dIKo~Rx1>n@LAAo;bh^Jzey zYsm$~;wFlrg^o4BOuAzLW0v-0l$zyFC;@e3xDL|%*cX_{TnBUW>}#yk=)H&t`m_#$ ze%>2C#BDuH%f5F!M3K+byX(Q@5}O9Hs=D~83tfmgVp$xXH!DBjGU zn0F-!hN$}wCiI8kKG!B0yt79D(NamZUC%}3_*Sc9$xu^Ah|5BuLZb3GqXp1K`D4?S zjs?=`qO$m~5tah=2quOPra<>=q%c8jfH7Voi-{AmqKfFxIxwH3I7%Y}QW98$u55sF zLvLOxT#Re0Q4pD@Eh>Z(Q(kWN~bW0412;B~=QNI{exKxiS)1W{2mHwJuL zx^|Rrcf*|>B~`W+F7Q-Sc!V5^N`V1}c35cUHn3lPGaqlsW>Fd3H~oxJ>ev}rs(Tys z@<0|Qo@a@&@P)#n4AAsoCx&-tK!0_2k5tHjL1;u8+hHNiI)Je|2cQ-1X>{`;QU2r^ zhnlv-;(GTemUGGkMT?GOV&8EvyKEDfU6l!q5vMTROUbOSz{L3qQEBvH56C>ZILiDQ z$P<(|{#=B>FUx|VExpD=B=fQ%a<<>ZfJZjW9O4cpPG&BjnMa9k3G5c*loic8f}( z{duGe-lC@GLT??rM++$6F(0IO&0j|Iq>$H6Sk|We;)B2EQH@hqcnv$D%0e2FJ_rbO zLKqd&=wf`yKyw!e*bDOs%-=!WgfKBAU~QXioi}QLRp0mo{3<-+*0R5jv|n;*22h71P8h)x|m4PrAy=yad`QDRIFbdf@^$gypjvxj-&=|=_vxlq)=Z0?1aNtW5jhoI74bZ zCZ?^Ylc@YKn7%WW&Y#COq+)?fsdPmwV0Zxfb~PQtgXwhGi7G-G;>OFkj8T;pGq99r z23-cNUGOhiy`VIdW@4UXAq?5rotOyRNr!z0HElN+f{gTT472hff@%uEgU|Nx5G9;? zEQ`QT$B|bNyn?bjN^vmV6SD3>Fz64-V5m(wNDfrBuP zF_joOQ3=%tDTKU8AsR@n9>&_^5X^PiYCh!JA#k^E4Igqfp4xLBg*~LlVd#KqEsv*) zF6{^S8U?r1@nCH{H%*TKyzL=|mmYyVtMyYJA&zc4lk)hGG(-tjz`lVpE9*U71UVMN z(zc>yG(tzmieXyMY3IQblv&1v`+FWDhnr6OG-}M2f5HOQM?vkw&zNABke0M=;`@?f3oh9tFl8wsED;~D(na|E%>&O_nF_Ab43gxF@c-l#b z@mg1^Q4T6R33vT<=*>y+E)XQO+sYyI0Kzd;Xhb zlY>V&$1E7@hyfTyl!L?TLNHQZPA$K1V4<3L84m3K?i|LQrs61?;=#mU#t=oJr(s=N zwTy?r7XpspnHQ9xeLQNq2!c{)V9aN)!9>;?aP5Dudp4W_!Js6}yKn~Hl7^>XLZkw6 za1nf|LaBJQnIVP3E5OWwZ5TOO0ZJ|5)d0ng&1A@+zT437*h=t32Xd-}HU3o|=E@@m zY(=Sb!`;L_r9?7Neu+wOMfC+X3W8`!>4-6qTKg95^i*PIvL5&w7k|JMV?C1;7#Jw;Ltpe8-qLeDw zX>Iw4xd*D?W~lKab{$-N!RHA?@)thdyi1T%#=(0A%BmBWVBOk2L=hasxD4aH4(=YR zf$+Nw*0sY4fg)H}AR}J93_~o*;34*ek0g%}Ma!?iZSn><08~>qfU;sEuO~XMfQ@hS zs$oa2%E98RtD(_cRf-@{y(&n;_X{la14xAD8z-K|LDI%KNp4t$Kg*C9jN zxbP4=qI(J^_TPZ}D)$=@XZ169$TY&w0~16IEE}(8VM5*qI`QA+POSl3=g+~si#4#~ zNX^3p`z8?U7h)puCba!>F(&G7LYGn_F>zq27y}vHf*H4XDMpfR!A?|u1tvUJh)M7* zjR~v7_!DjDDlApFN=z0x-iC<#l!%c{w;_e;t;NLa+c3bnNtmcl0zY$OYECWKekKjW z+iSt7@=P8fhI(otdeZYS(t8K4xhCI%6+wJIAL6+m%;R2fUAzOzWDoOr&O}cskATnI z?t=PfCoyvJE`05B7WLhQ?>&MqP{Yqg`4`04)Y~IHLj5vE=3W+)$9smK_dxe`*wa&j z|sAo5hw3}_mXdliJ?9Bp=uoL>?yeAKDf{wcJ?DOV#v7;-W?A&U?jT^hFata zj}Subb)+36d5wAq$cR?Vu&sy8bi7rJ$^Uk)9xNH`!~$RHAz#nw8d1{)_H&mvZnCiG z88uLvJy>d95A^Bs12FX#yy2&;8}1WRz;{hL4WL^HUh`A1-8V4~N~b=6+&eHz)0P1& zaJd28AP4XHDQUMMv5`E>-PTQLBuT+K0dZuqpHMpuKb^b7%F}U>For1^N^e?*r&zi=;P5%cm&p-)EyD-(S;VSJc1U|4MrgPV{)RP zurZf{W6fi7ir^-*kEx%7d=@D15L@CCWVaDE z9TjRYg^=+xm^eXjwZRX=+2twt=+zh|{{+4}hEJ;P8MM}*#fL~~GvR|SHL&gd_)+zq zz)c9HUBZZ|i1t5+c#<;4NR}s41i2YAWzkXtxYy)%TKolctl9z#IJ|(&pgf6BI{yXi z7VS~f3kd!>aK}L@1~qzoZsT~5YM$ZElafI0-b|5QiT_r~=PxM-&*kG^o68)>r^@>k z2sj0d7LY>*${Z41r+B9pjOM|wEt(HH6Ul3s z3P^M^3|+_CQ9gJGcQBN++&ZQl7P!?4tJ*@;)(T(qRFzX)4vMX23L~F3SZzJw8iR*q zS1@Jpt=YXcuvYCnA20AcQyy{NKnE+U_~5WNu#{R<^AK^=K*^BLDTIxp-@*u}zlGkq z!skXKh#g_r%p>5-=eLlA)mwOoI5KXBZT&P9+)mCSWCk&#p&fkj`agn!)P6F>|BbLP zn$`ig%M&5

rnZ0AJY(pzECwG)*0_jOEH=;=ZheDst=u6OX}H1{50*_~fY*TI@jA zI$@jmjYBciP}VzGef*B z2_`yMx^bCjW(Dlcao4mJ|DnE((ug{#V-5+EBi4AE|J$ox)bqEJW*|w z*#*XjyYLVuYV88!Z4m1tgpQCulKu$RWqyRiU=Du*Q%zT4IC2$8e=vekEbND?oG%nFCK)w#!?(MZ-H<#Fp=I3=xUs0Q z8@4v8n{YMXO%jr*bOOX@a1YdgcYIt!cJ;t|*PV@tmOKdt^7srgb~zHFDBuJ9CA>p| zKM{S+87(@ESPowcP+j_0Sqk-Pa1>DMXK1B3kH=F%#=X!vWB7!Ck`6DDklV%hmv|ye zMm6FGpAS$%*(ESovq@Z|u71Xf7U(Z>@KQg~}s_zX63x~C-gPl)oT_(YTXAneAU z=0jpmOGu-hKG3OC!GpQKWP1a1Sn4C9JA3ytGQ|U18y@f>s^8#lN2rMpncf7x;A$-S1{#GP@_0YD!r(uMC(KdF-^Fo9V54ik<)U>j8R0TWq2z=Yb5Tq5rij0QL72@gO@ zn}^f~;HCHllso`ulMn$^B*KC3h6mt7AX#FB7zQtd55hbZ5auCFbaN0U+eHyRWJp93 zuC&Gf1xT2lJ>|`Y2Zh-nF0XP3I{{oawkmu{R2Zox&w{xp5{Cej6|&djq%z@&RktRStY|y9uKw zX&iBMYLlcilA>|o=Q!y+n27>u91B8d8xL_HzHR3b;>ao!j8Z3{mUuQFyp-TL5S$%6 zL<}9C0GD+i2x!%|0K>|H9Qcs>04A0QLNgPNU?TPiSXn0sN;e(F2ulb$QGAlerlUw9 zjyZ9y0wWiMpt&2BmH9h9zb!!Udy zPe;{lAU%!&(ur^R;EQi1<x7#0H+DLwzg@)m~*Uwi)tEu+vQUq+$UgxdE}03C&Wmz3x3Rk*o3oe3S) z9vCGfitaPPb2h&*`dWe`ij*Zdj>NHHK4hH)XA05(mxsW&uT1nt4IB#<=txyUii4+j zkR(Ty@Bp8V@I=u8NzQcQqV#A)49Q7x>&yi0+ zWfB;8P?lp#h{MllcX+mA6KQk#gqO&3%xE)Ekvs=p8!zBvs4H-+iP*(F1m=zcB#@_JJOqBd7r`T#aO(lh zdMH8wuZYGl{C)&Jl4o<&&^1MlEwOFs|H6Gsp$hC#SSUmZJi}b}zXG?EAVf^!{uiFk zhI!SuYBcOYXszc%BG*g7#~CD;BMu*YQ!eD1vxDT=!9MZZ-*p~fYQ%)cbXqMBf#OIJpX<*_SRV6Q6p3@&-N^@pxWG4s@*`raED zn5M?DA&%Xo2p!aSQ;PqkrpWD4!~PAmsX=cYYAIn|6s-=y8+(T$#-c`bjxoHjrfG0| z2rt-Ejp3-E%!g9qC`khvd-;e$bkQRXm=nW~DZ-DK@(f#m#()LMuQ1U&hGR+Sy~c!# zCJ;m`ChS|KB&nXmPcAee$KODWnvmR$-ePXlTZn%TEoh6?fe~XJm`QUwpi(&nf9&Lg z1+`(-y8fOIp?`q-OSD07PZuA2jS`Ic#D}Pk<(Lr;J$%UOu@KJeULGQaTE@a^^1Y9T zI1>$DFp;eT0muA~iBCE(Fx@{WLJ2wQa$JbQpFBbaozmqv6M=tth%{0j2kG^t5Ngtg zg-J@5C5)oSf$w^le2BgTOA@Ue2X2}p#p0jZlco5iRP|s|K9%7ia#WR(*F2;Gi+{4y z(P=%1#{2Vm!orBLfTfJw^ub#P7xBSui*VZ`C#|#kFi!B(7=2C{aXXxnGp246jER2u z-LO8a$khhmjhB%Wp@Nc@u$XA9AuJcpOL&L|-YuUqwM)H`AEo0zY}r zHs&m)<>r}yVz`zu;e->Lc4C2sU0_ecPL?#PlA<=arm!0AfKR`u%D|IBfu^8aat}sk z>;aE(x5|x_pv7L?B>VtP1|{u}XqNpS?N0d;cNr@t{HPA#!nNpET6iG#- z^h%~kkMS>+2JPgZHn_k>mQQo~v09)Ua& zqMEL(J|XTYyIYhfyVT-n1RP|*g0l?VFaqY8Th6NW$mj#B%$+C4!k?PnV$u7|_pwT< zWi6|GZMBnCuCP{-B-HI#!!k8(jXFU+SffQ0gKG>ixyWQSXA`1{&Cbz01R4EJ51ngb z&;~#HqC7sTmmK6N4!=^U6!^JAEM+N0kPvv`Ie-!6LvNN~ z(N%w63PH;RZYA0%IGuTs~TJ!|!jq&eq(bWfZ*A-LV+__E}fnq}!H3$jbzmz{rqG|r@dW#NaB ziepiOccSmvzM3yn^Vj95=o`3L$&wGWF-O=ZfzQ|>CAZU4Mt*ls$y zJhEm{-djhmeD$4D`74flcvd&e(s^;&FFay7SN=?+eRHv$juq>SuAXC>iJ!XsEPj52 zWAxyhR)Kam-hqy5`xm}?RcWcZwIsvqLn!Y+=RPj;RY6DX)|TeZfAjLp7sl zJ?B6ESlnG=Wh-djdEnB{>3P)e8Y5?JpH@rpiCz=EpI7xKItuFpHcc%^Zy zY;4W7lLLO5WgCuo?_T}t>)!h5OVo`{Z81sOCsGs$_idwp;55d@gT_ySQeU<|uEl^j+k&gz>QXy}KK= zB|{fIxOBU;E_&{&PO}g5msgU`!mh2^3p?d+qR(Q8+8?F-7DrRt;uZOtCO5} z`~8lmE{}Av>+~!eO&aC)lLrbj0 z_!Kw$N>$IXYguCS=#zSWz*XhAAE9gFJfChaT`9A2!Qq(ArElY-U&>@&c_;nq>E2)O z*Ln_N=hN#iL<`By)9Dc>eMW*jX-Wl%e9OdnM$6a3SzNuK#^d>D^{oaJA#7+5to^uxR7aDUu zKJERw!g}biz)73oL%pd6)zMG=0`>g-manfZkj;+^{q|{h@BOZxR;6XXUrO;r_&2{a z6cYP2(sRLH>q^#vwypcStuCN<(s=Rl8~odU@N320nh?~O7gIWHn=Lvw-lKKl%Gd79 zgxc)O!BTsj6Lgz4nk*3%OJwfYDAU-f-8Za}Wo2;a=FEnmPFbuoQH>sdFxuK9%|c{h z`z1YtV;(W(vmSVzFL#fT5xDF8pU%nh7v3X$F-YL9>qs7b#K!&p%KzF_2WzpmX+aCx zS7Z6oI}^%tu{O=YwK1>7%J$z1z9zHjhUP7yVC&U)6RKKty>CH>@m(!%38AR3`RaX@z5X4l$- z`KxBTR-YA5xiGZC4EGN7-+G6(T{A9G-BU5eNJDnog}?+UJ{!IFsXTA@tzYpgP<4jO z=UrpNDX2j&dAnla@bj9ti|mJ8e%3vDYn*IockQIH%Ye<&f_{nCKPAcCy65ebe&jz` ze#*W9jTTeKh5oM4#Ki4jv*O14Q_jhD#pcn`k{=ioBF0{`X?j}cS6Vttx=V;VS<)BN z?5-=F7dr266j@)>zgd5?eo^{KyFG84*3NWz*>tNZ=ha(lhaAJvZveJY6$ zyBeJ>>8JNjqti??M>qTZy`5*{@2v9PB>r$r>Rs-8?vh21_*Xxxy0`cD{`PIxv5F13 zagHO2ag8PR)H@rhxJL@&jVzrPQh~nHg`^ z)EDg0`Waytao?TKNodHds4Zxoy3+&Zbz_~uZuQSAnpM^`JA^HsU$rNrX7pFQPS_4b zz2obX>pwcD`h}=5pH4q;KE$l$!m`8us_vVWc7ATiOd49&e7t`4#SxveH_onn@+;n> zs#I##<*X`^%nQ6~O{vj>!j3aLdTPqjBbwAa#2%M?TJuo%bNrl3!du%icb#NjIh`mh z@X+sg@L}y{-*AyvZ_UDQhd(&6H+3wuu}=Pcrq=OllslvEOtQhPlMhr6WWU;!e9&z1 zW7&oRd3k(Cd#!kP%3^2XJM~K@?DdcBeR6VR6kUL^;nkp_YihmeYPra0pMyO%k-}!4 zg4V)YBe_u3Jj6%4JwVa9JF8Q{^uXe(1 z4~ji^EqWOCHSXX*$5?#fLB;mi*-@Dt)gy=ZpZZFz>^n11aQ6KcJnHBM-M-Ev@~K+} zmo*OB{?73}UwcdcV4%;4VbsOwj^dH@gKeFn;(2G~`fi;$x#Vzi=yE^Jh0SIr%W5Cu zjDOI7>tuhcN`3lKAKi#6Sn@3WHCAD!7UM_z-_XwOcpTIhq?~*C`C#wy z|GvoPbsVnzb6Gt<`s-s&x}vs2=oa1dcW>$QUs|}`;X%UdbG-$8v}zOGX!#2oMpa)bS_~G=|MTNWX}0RVu~?ZWnIYE? zsjKTSCbZ{Ks*kz}JiVOQzvb}$?KYY+^3P5+>`8QZ)MqZfeT*?K`Mfc3UD(Qo{b`SE zE}LeDKYtWzkLZUhZA1Rc`pLYq-#zQMwzUCw@v|G~y|DjUvthq?tzEJS&oWojO*DUd zMZ5Pc|C!!2-NEkSxWb~Z?}L*~3qszDtd%`^_uadGKQ zWx*OD0bQMyYc4QOrf)_!o9E2RPucZUMSi>dMHjL9q28kzKlU#yvJ1;!{ANdsA+~ad zPLbpI^a3641OMHw+G(Kwz^eMu`iuK7>A4rrPwI@mqrU31i1xu?)i+l+uP)JD`hA}2 z&XlA$8TT$z#p?t+f8`|Nw~-%#Sz)^z#KKOg5ec!nt#3xl^cSShpjm7xoBJBoj~T{Y&CctVd}Yz*qGw*SXWRIHGe!ptcP#x~C%${H z#dR~x#7HqJT1b;xRQSI5NSdR%3XlJl`_wDrre4D5o0%A`>snw@wRFxG8BAou4E9{d-B2>t@3MuA_-= ziqg~cV}>s1HQim0HNEJ}l-6lRkFRc8tst~xPS@8*Zdadtb2f@!$b7=IKJt8Hf6l>~ z&S$EHA3AT7-kxwiYYSbxBrANs{mA3DkLs`MXG=f!41Z@7f4Uo4#3gLLdd>Hl$7obX zy4bsA(Ye&zXDajEqmvxuEnIU&54$Lwa0`*XnrHXc$YyO+;AN%hva?J+o;KQV>eSf$ zK&*Kril0w;{lF`uqr4>&wj-8--@#=TB9M$&QivvnL zCXu%rRcFLMS<|4@c_`le$}O+PClg7VQ{&^~qZZHBS{|^u#&L7S+PeJ-af3bz#ikb0 z-;_);&d`0c&RHdPYe%;_&-wG(KBB#=(saGGcdlrzO6XP5T(uh&v4JW#g2h`t`Fb}} z=O|t)J9Nq2z+U}O{g?0?(S7-%0Rji-@>=`p-r%*qBm2m)SlIBlIj__+wFqB<3@e`J zFTRC%U;0_xVVYY~E=y}@L}~3RLH{k1f9Uz>hv4$|4+7>!E`t?XUB3soE()hEV0@ou zv%V-z<8qSfmpg+}Mk%W&`2TG_fTFJvYfRf z;wHJ!GGHu`kQNkgAA;Et1EsAxZw;3)W z;Nzp#1iElEk#%f-{p%E~QplfVqJ%^KGAM33QDh0SI0&OKSw9kZD0JfZU3`{GDJS$5 zyVEGqtRL@1DRrzL*Ci%vJ(Hp+5VcUB48?|!HISv~6HzGkVN$}0BX@C^JSB-wjM&QE z)0Ve80Cz7mCKuOS^i`Cig6Q8Ff=Ee$!jDQ-DfH-;+Q7gUcTc6B*n8qu__>x$pCdPC z8Pv|%u=0iU_49Ov2etjR-Iq?c>>Ow@sERxEo_Th)1AW8B-K);uWUh}pM15jSUtqbA zXO$)IDxMXEx*-E^T29wq@)7)kj6=FJqU+9_G~VJhFmGq$EH0-*yiuVYCd-Crk7_3m z=-p1O*-n`jJ%)XH6lGC%j9bg3-1U_4>1BgIA}j*S6HMZsWgcKL;J^L$|zrU*|{n?-Rn&&6qt&Z#9>VITr{*GDxb>x8PPu?JlsGf)1 z6oYoFN5A7%n|8%~*P)l^e=QI_##0dgrT@XjUGZ(YqqFRzqt_g)9*pc(*zzrwE2BL5 z_s|tCSXK2#^`B;VeWMM0(@MU7;(dPB$U2RT?|F)M9=AS;{CsY6lkKC}kGpqTo!fL| z-lghQw)QiAtqQrb=SBKrZ<|G~hIX|-ItH+tx2LxV*dAfzq!{qrP1?N4;h2Ed=OuXI z#wT(wg&PG$@T7BDSE5w{0&=hJwb`cR!<&AfLL}1J`ti=$(v6F&zMV|0d$7^lTC>Tc zXn)?~E||?E-j#V{EiWE% z!&|e&W0mNFi=g2o$%r@gM1z|FSMOQiw;jeiXELPgMPLtR3Xu>up^UNzN%*2}K8F~9=`W`)X zDC>Prq1_QRmC~Dz8`oznSnDnxee2>?Gr4||vtc%2+4)DV#rf{@)eJm9+a15^tdYlz zdCC{!2UEikhSap$Mz{`xYibIYE zZcCoDRW#2wE;;IR;OFX<7gxM`(Koh8L6Fwlnf!i!!*^j%o-8Nr zJ(}`01~SDrZcrr?in~;EwR%kUc3$&2^);)eukdcwP50B0*DoB%xFd0FbJ*Cmg`K&^ zZZln?*LYoz3v=1Npjzg%~3o1Yx=PM>E%k8{1{?=0^qMN`SK+%mgzLDi^WoyY9* zu5G)lDyZV-zpX2z{Z|KRE_bANW=&KcG5>8_VQXYvF=vL3zHxHR{gXfR!w=NBEE|8= zbDK!=M8|5y@%(nzyN(rBtzQkNVMc9g`=`Z4FVJ&i%rTI?9A+fD^wKBFiUk7N z(#~Tx83tzu)gR2dXf^nE8rJi9H`)3O&2U_2c@^tLMLG9ew-C zvSLT2)C%Qp^%9x@uh@d!7gkniyI!#D)TLd|Tq^eJf=$I(P@(-x%}v_cP7CCd!&Rlf zpOib$5|>>a7#$JZRrhhIOVD$>P19%1R6~Y)>>cl0b#FahdP|o1eEU=p#5b*ewA16&OlEjqZEx_Y>(;xnes+9% zup!cO-Hz<%``0^nbtj!0R(^CK%E!aLzgA!!->YdkQpOEUG48WA1$W{%6*B{TO|xpxP#vQz z9V9$_Jx*EuH`+fdBtfQFW04a#^;02JtF-@U?}@DHeY>@$J^k2qIJ@aol5%P0u8Pmh z?_$HE$#$om{iKHGk4C4j4e2yUF$lT;VQKTV>9Iq})*Bn1-IsqHBUuo&J+@_J`^sMm z*UveYyWW$Yu3sB*g>k-5xj#Nr?AW&CT>PX{PGVYV&bHp1cRF@ije}hajE+XhhBfLm z&--=py3fRutS3uu91`M9czL}&G;(=Xqr&qO9{1&*AMbp#&2-VxRWrXtC*|BQ%h@KE zsFFgBeA#8BUY#Zv+m-z^_&vI(O9#tmM*Y#ECfru@(tj!k#|r zwNgGO^fkOzE_e~gotA8q^>B68iZ4NiJ}>9JduPxq7q}k(F5jPR(0h1Y5Z9v1h4mdr zmptqYs=l=1ebCk=51ZfZ;)?0*jGj^O$w|&4rpo7#nM1_loHM#HS!0hs*=Bp*#%v$= zt(bjB=H`L{8-d~Tw6PTl&AOt+jywA+1WIIP1}iRq^hYv>UtL}FxS!&*xn}WU9b$Kx z$By5sUfhPDpM6tTKCgUdz*t{)!KhRyt=&g`C*RP{rq;E=?c1!a zyu4P0z3?4(vduw58;)(nXI(4y#BxXHomB}lJ%-@~}E!BO7zndj~;kS<&H zeNFw+md=P?Y5S_HCqD28Ts`f>>oOzPtAGBJ&F&!s)ARo8)}B^py|OpH>*R73x#-ij zcXZB_A4V^n6?%M2C}nvE{nSjB?p$GIbxmyC|DAw(@inE_ciUQ5wsW7DdGwci&-K!7 zf#|!tB|fkJ;uDxQaM+;g(}ON-MQ!&H-<=DDpJcnAw*9lV-+B8Rk5?W0h7}Z6byyD< zKKV2e`=QYMxS3Ppk8d4su2kLj_^)S%bm{xPnn$A-c`Fuk2$gP|@ij{A{A<@!`5TYe##mf!*KgEtHd$y@a&GVQO~tDUjylOK;kEm5Ft_>i z<#zwqLtnQzHXnPwLb&Vm_fenK=_m4ge_Q8hzCXKU$Su#f7IfZQA#y#ra76hc)xh2U}-Gisl^Zx!b2X;zIu%*tOWW>1A@X zlGe^D*?TUXX=>W#g_~qj4+*&`_?63i**1`c@8k_$$go`>U3K^Uw@laKF z_e84Q{RGFp6PlOy_sBh%ar{Sp$;rGo;=Y%c9ePdSJPj24>rlQD+wj;8h7@=(c(~!= zfrl3!K6v=yp~52ok03lk@X+89hDQV*QF!R^h`}Qcj|4oD@JPWU4UY^wvc($=8Cwvs zseb&7VGLVn#9hm<ifS1aMERqZv5qKL)G^$N z@N>{g^i@V#7nZ#(3gzW{~Y-El0m%2M1Ni~ zjEHjXD~2giZhyrf&N1ljD~2sW3p6pD2->}gv6?7Ln!pt(WnVM45oP>qMlexMyk}2>8WkM%o)6^H3 z=yxY$gA)6y9A0eOh;wo2a{c=!Gsd|%Ip(rPa&)l(%I#v%2$Sw~G32oE`z&0wTplTY z0DRIU>~LlB*WJpjQ?7`EEd`V0CSI8n7xE|uOvY;2{OPQghd%iQ2>tgNnAte;H!QA~k#{zng5I@ESW(hgN)Is3Z^8@o7zM-@ztS z%h=iv-rQ;mb8*d?(pEjYmK1vOks&yZe1p)iILg5c4EqEX45m~#_LAKUy7!U6AmZ}h zM}{0l0XckP=+5M9n#hE+it8NKgPRi2{K6@ke25CGln5aXoWnjk*B2|zR-!qbWVbE> z^!pRp4T3%3ZWNm#j5hZ$hDBh%p0PDJyAcY4-~r$Bdb2fO!T&op+tbJzLgk7!8D4- zl)M7oiZ4*XndBwY#{`hacU+tm&|PM;Z5Ke)v*03T-jwEgf3Z}7xC9dIC!-+W4|)#% zAsN^HNFkx6xFGb`-}!-?$wfgi7)6iO1SK4qr)``-bda-rF&R#r(&%6|CDkXIx;QlU0R68_%@S!J4NRjLyk%oLyWnUBosEpFy$^YrJ#msxGHimqe!CuA%-Tm zgxNnx6?qIZ)G0eq{4hh0l7`BL8HSWH^kbM|Lg_`iKN;4Tf_ch$d&v;-Wd~;KQ}i;t?Rem?J$Qd^WlS1jPh3j4)g%2Z%xgt>?%1(ArVJpA&$3swB>j zZUBujEJ<}isu(Y#{Q|^&5;{5 zG1+5((M8zlL{du-4{k{@M1?$1mj@~HLgh>6kQg7Xj!Jm(H56k+=fi!m#4J+$c^1r2 zv!o!rReaDWj@tR~9au&wkrL)8l^?gj?%yGaL@LgQm{i=5;)7OD@ne)3sDp}!Vl@v5 zz5zNSfZJecHDofi)nIGANFX<#6No8VDvZmchz1H>=wJT@AzdLn z0$cTxtkfz5I)&RvThEO^GOeQF^RenKHX@9k(QtF@zYlCg25EOwgvqYnA`Agm8RXzq z2;&CWtsyodhvtdkb13d8SOk2z|BGZO{iaAE6;WuaV~mYJ1P2&26vT`3phuz*t>dUe z6pzFN_)vuuj3!Glj33$aVIrtj90Hm{hqe{?r}C)iHyxjg&7uA;>?ejBVIBf(n2K@) zFbPuAPchKcCB){5pvB_2HRdP6MkG+RIIfGqP+?i3B!Mr*q$D`lmn3jK%t(qrw2^}> zHXUh6;*n;^apzm zy-~pRF)=qbB27$)n%Ke(1j3qV%`xYVY(fO3Zp37fuoB2PyR%^`N_5AB5MB&3OOO(- zfZg@r;1ww0W?0^44g{om(dW&OTyW=F{+*ltl9P82~6Bh~Jw8jl3}~kF5bZfj;P~DohK`D!2&64Q)}uO|Zk> zq`COE4pS6G5Xk3A z-D`Q>9YNyzTOBvFDdOj2(&L2ds55>`A2BZ4^-%+5$4k&QE9veG#|NgN0EeS&S5 z%0~E+kQOv^?G%Z$oPtT~^cv6{p#_>HGe|gJ3l@^?=Sf0f7CsLP$RY?FZI}h)V(k@@ z2+#(f?-EGWH4bFr8bm>TIVhd04NAQV*gR9LyqHZ;QLQ#;4!XmE%+!JP>H~7u!Pj7& z4@id8LyS(iNkfA=knsDSkg%pMR91OT5RiY*F&a9i3%;f_lE{-r@IGuM7%`*^bH6mA z>*1?0?lyv}iY(e-?q_jryD`oUiB&gQy;%=8pwuDyY}^T3Hb`JNiW4S{p9}+(B2OKGRKsv&Ms1$C_mdCk}o*}fN z3ov3{hsq|rQv~#QNdYqhaNJ*jAXHJh0p!Un5t0})0HdcNT|?Nt6yhZI1?Lt-bQe$; zsxU>JuL3C`F$c!a>S-hqI0v7D{ZuE3Cv#xNdZ0xT<67KODAFACL>Nrb6J$UNTr=Q? zRGJH2z%U|_&vU_?cSy+ycgB3Jkg^f3giaa3>fMhTjPP|BT0+P%(UT?M@p2whvK{LqQaAau)34@NJ73R1CsyzydS>v|J407;2`f7%+r;H#6b1?i$1}W5* z0nHfAg=XHHL+cMOkg%KubZqG*f{;V~mp~@k0%9waOClDz+~VjBfm|tKBm79+5(Z<) z9TJJQ#1~?{m283^^;m+%Nsl>@XOFpQq=}oYpmo^>4&Fs8$mySNNo2wbx1#7GtNGAz zD?e~ZC47Jc%WeLf)y?xk4R;SIFt>*rM>;2gSFZ)TFf(i5#rLB^YsiFfYsds~RA7y} zVnQQCCg3P>0Z3^rz!zhsV{F74%bH*lJg9jBg8I1?;^oQB!#RM~aibNBAe{yYCCe9r zr!iC#$yx~0;vyPJM9_HX&jYkZ{5B`ly%3{#LiwYLw8!72XYze*z zQ=LP$mbe6VhoMF!F}MWm_-w-F(2%7K4q+917kKDB3-*q=%Ruc-FE%WT^8LUPnjOHWx03L=?L53_u^k)`0=BaeS<)xJ@F}gi zhqDE!=u9||G%01Y9Moy<;oyZW$4#-q10+(v9CBYYo=pfK9eY@Emm+t2$k`?7?0USY z)gIiqah?OQaDe&cV-^RZc!@_I#jpL_e-9m?@#EPX0uv4}KRvxhA`UAc-&_hvBEEn} z29>RV!MWlFiELa6E2Z#Cm|U^jY{UxlyvHWQ(DRjGttFy3!rFJcieTXAa}|#qN^}HG z^PiGPlOweH42CJe9&dmiU@bI}uct&X_%$i8dld}f@^>g^HSF#t-tmZ#i+yPO6lvdf zQs4@}Nb4Fgv{pm5_MknhAx&rY5L^|+?*u1+Szk!P-w6&|3ExSg(Fq1Y;ZKt2`w2Fg zt^t#E$4KPJ8i-BnI7#%bfw8!W2U)p+{qzYQ0hG?eD?%pSbSf|BfQIekKdFn(5WHXF z9LTscbpC5;4rGH1Y=70|IS>zdURHp_5U$KC%5m`^s>~s^RGC*8X|Dy7%T-Bua2@O; z!`Fhk?dlxJHFaJ|q*L~HJ{wyLIWb*}L%>ywSBhN9)~y2`F<}yZveW^OiY#?`X&f3# z38^f7wv;7h8PapbH)3#^^RK3n3D|ev73}jcCtxPxbHj}(pOK{-?ub!s2uvQC*?@78 zR3^+<&?e;q`sxM?ukdn`>%AU2VbMy0kVEC`A#|Ttvk4lS=>&GMR-u%&Q##?uT0)A6 z%GN?8<2HZ|((4HXNA(+^C)?afLS-W)TBkQ^*aVjB*$8cI@h6Eh{=9<3_Kl9V1W(cI z7EB6gxkJ_0J4m9<9qyYF-C=z{hAP})EoHJD0>XUf+&{7YOKb^!zgi*jvkoQjG<-EjLj~YC17wqCG)Ug>Bre&MK z`g<89k-Zr<|Kg~9GnkTinNWnIm7cIb1zjVFTb^M3(E^g7d%^Vf`UXjq7eKE?dqLWI z-{C-738eTQiRf;D3MLh7Ha|MK1&&bdl_WB_1rBGMp0L?`$juvq{;ZZn3cR5kVJ?8~ zV4yz@&_T`8f9ET8AIPlAcO=iv2b6B=APJohkcW4CV6q(VA`wwvd=d8P3!4p>cm0qK z4jvGzbYIY8^qtM)MSw6SqQ&U9&(*TVY7FS@6-2ND!#rZcV7h(PeA!fVBw?4FWYY7LjmH5E#_Glpx?v z&5ch0DcSPLBiHwE+GZ`w`oSQ*%AP~us68L-jSzHzq2rXu&2*e9MMVLQVEcH*-}w9? zboD#2rKC_zHZ0L@+W_9+#)jok-Zrp2*PD$ zMiskZkZtTBvB4HTK9t_U2m8h8u;h3|fmuJgIe3{-xCuoNwMRja>XBtM1j%8PVOUP@ zctMLgl`x(PhG8t{`0;a&<+FaIl>cGe8jh_6hvEA8XBdH*A-6b~B+l$21@hv+i)k@z zLKJO@;g=#5)6wE1;EHN22hS&#UmV>x1)f?wKj(5FA5ThsIRY`ec#I&JsOcCuXCDvF zy*NQ4sqw(pN+Ug8pT;kM(q@A)ECCvNd76Zc5?}x%pCyT^v(T?+S{by|i{NBY0?xp~ zFOsaQ7a>p<%l^)q)T5xI_A<$vxC|{XI|?mtxk@4@ukuTxdx?LgZ-F$04>cTxEZJK` zidY_lZA0~Kl4vjI7e*J4!R{lkoQ=qkoA1+=Q#vLI=_Nwy^P$8<*!b5!LrIC?JWmq1 zF$C{olA*JN|Kq2jfFyAK^=mdFi{2%Hg~yvo< z_XTW(E=^^%IeBX!f$cZQWG;%CE-9-FhV2^kfrJ* z5~)rVL$@2jtk5*jI6RYt6ZNV5s2~j%m24djq+N#!d3+M;Z_sDMQYhXQ>YqFb^<}Nt zun>B45{{20u)-5g>^cR9J-t)V`8OTdh$*J9iX`k;QKdO@Y4j8*d+E&P2_jJ!Dvt6` zLqnTR1JBu&QFXfhxtd4M0x~75hf;0Od^UvaI`QA5Y~~i7T(cd2ltV1$v$w3 z1#5s5_V5r1Z#WBy!i*;fCR!d(rK7Y^@T=q~m2+;&LxX2wU!{41tmJxvDozGyqcaTK z{pTR@q+szr2b=Tz=iq42j0Vra9ZdcOlynjF`kcp?VOB793F5_hXwevk?M2wu1zd$l zYCA%UngvwO2}h}b5P*Hk1z1hC-5`nV8&pwbq6gCIx2H%ez^J~6&qTHt@dXqalz0&j z#@0S0G3`u<-JEKY2(O0rSW&o}2~l_tgPEuYuq4X%!{JqD7Qn||knr{_7~^J5B(bN7 z%DP6QqftVp_zeLoqro>&b?GJOfUs5)DQJbnyhb4FI@vOOXyOvsvGOAavf(oLw&OF2 zrccV|fO2C= zc12#aRZ@UP-j_RUf;^~^5fJ5g^<0KlT!ll~3?^A)4O2jrIG@r{$5k+=NQr=%NcI{W z&!$f&3FqkolH?44u7ON|1___j5P+{er2pRQerS5fzSxjJm^?1 zj3Fya60yt!>%uJs#L2D~$b3&EO%NC6=fcpdU-b2NeA=*D$;Gv^;e5*aZ9 z!br3T*jce8@;VkG&D!+w#tU!`s<9)az$}1?`G4|o^P~vkG4CjgmwE%vd!JyxPPBs` z2RYVg=}DcUs4bNg$h!fZmw1XK+-|~~>R4Ym%0y&Nkq*ja3(Uh-z&4xEU33#tYdD`I z)C-^?cx4JV1w~V;UM(U8T8h9WSn%m+=PfXHOEC%O-GUxid50wS-w}`@lxSi#_eo@9 zF(kphhe+=ZoMauU1w>HbOK7^K7*sH;*)Y7)DS=v5H6-$@MqqNGK2-vO>d#2n?HME? z2+~n+-INY)M`E{O-+kl-DOdgieCgN!o2-&eQyda(BBd;vz?y$<V|r6!?bVDWl78 zphsaBHo3fRB6yjwIk*E?gsk}9A&`V#5*aUrTgm-M_YT~U%z{gK!q@COaJEYNLl8{F zdl#}L2KEJaf#Y-+viTzqK}^q%BNG$Lk%m@c12!e^q?}2o;G)XXI z1Z9YuF->e5lSFouK{H5!AaGQpAUL^rd@BR1dv& zAm<=~j}-1h%D3vGh6<3Q>j_RSFb?JLMsb+|8|Fv)YhV(~DTgNV<`S?X`cMut+EMtp ziXhA?ASIStkOZp0jVR`*z5)i|pbddB(ZUBH&|pgvrysz@imN?IOgw;7Pn#o2YRN% z(8ekVI3t9>m}psuAdPq}2fLmff}Eq(7jE2$_Rj1OlpvP)$#huu2ow&4le~?)z?OrL zz<=#sY(#>%jG?37gdmD$!#t=K{@)4YC5mG;@NVtr;3ZVUSh;bO1L-{q((uAU6N^tp z4Uh5Zh+B&}`I>@}F~wBT3{qfO22^297&jlo?UqsCk^?0U2q1nbpJb3nLPosJxh?-Q-}*Hfv;`g z{SAD8M!>3fN!aPGpd=~?1b7HwN)@6%g>C!%N>uR_QhryZpdiO3Tox#TmxAR_VeqVc zMu?~&^Jj2bj@6Ue5`ch1a>X-vLs9>h#Ll(}!aZ><2U$h^K@!G41ewIKb+X^l&nY2K z_(@8Y{e%p<5yl7(sY|Wn3gE@WzB%#&-shEW}G~ny8 z*|PMv4{taKB<%%^j{+r<`11n%|Dj3}Gp7qp_Iqd} z1oS#O)(D5-csSA$^>|*w!B_xUy~N$Q{DQ8K7~ju2c1FMv+V z5uwrH199@7%$Rc`G;~{p2H$Clz$M1vSKwka9Sy#P@DZkFJ#XN%d-5Hq^=oKjGi>Y#jldH^=agx}DDgEk zR6C6WZhsAG8&%neAbbcz<3kqzf#4f$5*E~2j=yksmn2ObgvmS7p*6dnTY2duFJi~1MX{FVN@=Ehud&BdQMV#@9+iOp?);f5kON$ zd44p0B;SH-az74WLF(w2AdF4c`{BJUIL>VoG$~r%f}3zFhD=h5t@u3d%+N`yHIycb z;#)yYZ`dUCwiU$ZM@~|^A|W#NZ6MIJYZ9XGroqb_;>B@A8?@sU#ln@)*(eC><9C2R zE}(I)8f8eQ9e3njRYXG#r8Fg!P(+)&C3@5jX{dra+VPFtC8aF3Aqww+){M(olp?C? zfRHG_b{E{1MfCT$8Mocre-sUczQ^^r_1;ZFqOX zOPFOVAT;#03w%KmY=jThNx&7G=?8#wr8wZ&54ZvMCuw0skrCEF%icf~e|~`IjxdFh zn4GW{vh0Q`%N1CZDv>DC=yEp*gsZXYD4+s0Xs@4;x}n8_WKpY*un2nbfgwSrh4V*{ z&(-i)-P3}l5PQ1iQn1SL5+~4{iZpv-GMi?ot6^3tvd!ciwYgrV`SiK-A5hzTKg_ph1 zPHpfcwdXS~i1a=~v`a(&LG!rh?D#AG8N#`3&m{FaMpz8#_ko7XG5;VYc_yNNhx^RJ zJ_t?dzJE+Qx_gk#4WzyM%wSzkvA9q<;|H z%^Zh5ShfZFGrS+#*m2??Qx=t-fUIFLn+ax4>OZCck{!U!xed-wLP0=LTv7f2ZcoWW z69dH7BtLZ!mV;e`aM+n$$olP9C`?C3ohY&z{TA? zJ`O}?6c86!1lf85N1;}R2pd_8{Sjjm!pQO$+$f2{A)KgSAt@q8oH-{)+DCN}&i!MH zIw7Ti{``VA{>&ta*xkpDRJ8x6i0BlG|wfJ(<RSK1*UkM zjqsy7jH!!Rz}GF@OnD^F&72M2syc8pmt&?`ECV<2z^AO`fMao&{{bT(VItP#0RwaL z{-P#WWfAN5O&+E>_UHx?B=`cEmuZNNl#qlgFBmlA9!cc!f-OtR*aRPnE)$U=LJS`o z^MUH*`y|hc4^$XDBni7p5g}C0$JE2*E7{02G>adiVpz>aXlOS-Q=g)S3i+9inDHx; zp+IHM#nk^JiLF%T9LxzmZee9N6)fA^j#daTl~8Fr^pcN1WG-u#jD0V{xkl_p4g$;# z@HYenL}7^Ng3R^Uflnw#h^da!1i`Xjy(9r^v;?U_Pzd}v03W{)GRuXSdX%4Nj}UV$ zcI6w1@z9{2$`DCxph09b;DZ<;rW&fIK?j+Sp$cK9B9awmT4K55BoQvmw1Mx+%7wwh z_cTOdFd3<$Og_XA7L_ALj3(wt|BKR5mIze6C-xUuj!`B4{^mnlMVX7R6_NxXhw7!7 zJg81q6uzX86s4kgaTt3)MZtk-(*G+kj}D2ED$4;Mr9+6tW^f=ZO%5|e#n1#DY@%rV zFV9j#R0z3=0gqpwgJ+>HI*s@flF43Z76S{A0f)eI15vmV6^DA>b2;F1b4A4oqct&0 zJ*1C3z|%Y1(Br$Qo9);UWCeIK-saaBw;DboQKhaNn&d-$g-Bp53)?0 zVwlQc?!$iUAeal$69(j)dK5v-KweRzI5NdSt7r^~9K~U9C+;JOx_!{A-XH%SPNbNi zEd=Q@nV#5%SVBY=SrQ-OH^qudqZ%ft5kAZTi^(x$^d?eg$l{R=rT z{2}5%;^mow$WR`}>z7MY;d#X8ajaIMsuec<4x8XZ>+Zmx2-qut3Ay*!FfU3|0QFVn zB*L)u%xi;K^$0`K6{Cm zX3b>UV3#~Nkar%?HfWlhlc-)()Qx+RqVUHrLTGR%(;9o?Jrxl~)x_NzYeI|E0y~F% z*a9?kM+<`3>dQuWQDgv}h7|qi(!@am-sI1MDmDRA1(b%NISs?_C%0aywkfONHy9JR_|ywY=`aGLlW@EI&^ev4_%V= z=eVQ?**c&^0=~N^lz@O8_8^`lSbxZ~SQjE7eUt;SJxW*OScp1wp*~9F5O|hIhu3=S zmC7i2N_@4GIYcA$m`ky^6CB9>6Lk61+2BBG%2bqwR?mjK5 Date: Fri, 13 Feb 2015 18:59:30 +0200 Subject: [PATCH 15/29] Commit because I have to go home, still fixing PickupSequence --- .../frc/team3316/robot/humanIO/SDB.java | 3 +- .../robot/rollerGripper/commands/RollIn.java | 6 +- .../robot/sequences/AddGamePieceSequence.java | 20 +++++ .../robot/sequences/PickupSequence.java | 37 ++++++++ .../robot/sequences/pickupSequence.java | 25 +++--- .../team3316/robot/stacker/GamePieceType.java | 2 +- .../stacker/commands/AddGamePieceToStack.java | 40 +++++++++ .../robot/stacker/commands/MoveStacker.java | 26 +----- .../stacker/commands/MoveStackerToFloor.java | 14 ++- .../stacker/commands/MoveStackerToTote.java | 3 +- .../robot/subsystems/RollerGripper.java | 89 ++++++++++++++++--- 11 files changed, 203 insertions(+), 62 deletions(-) create mode 100644 src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java create mode 100644 src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java create mode 100644 src/org/usfirst/frc/team3316/robot/stacker/commands/AddGamePieceToStack.java diff --git a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java index a1d46c4..2ffbb3a 100644 --- a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java +++ b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java @@ -46,7 +46,7 @@ public void run () put ("Left Ratchet", Robot.stacker.getSwitchLeft()); put ("Right Ratchet", Robot.stacker.getSwitchRight()); - put ("Game Piece Switch", Robot.rollerGripper.getSwitchGP()); + put ("Game Piece Switch", Robot.rollerGripper.getSwitchGamePiece()); put ("Distance Left", Robot.chassis.getDistanceLeft()); put ("Distance Right", Robot.chassis.getDistanceRight()); @@ -63,7 +63,6 @@ public void run () put ("Integrator X", Robot.chassis.navigationIntegrator.getX()); put ("Integrator Y", Robot.chassis.navigationIntegrator.getY()); put ("Integrator Heading", Robot.chassis.navigationIntegrator.getHeading()); - } private void put (String name, double d) diff --git a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollIn.java b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollIn.java index 0edd856..351456b 100644 --- a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollIn.java +++ b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollIn.java @@ -1,5 +1,6 @@ package org.usfirst.frc.team3316.robot.rollerGripper.commands; +import org.usfirst.frc.team3316.robot.Robot; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; public class RollIn extends Roll @@ -17,5 +18,8 @@ protected void setSpeeds() } } - //TODO: add isFinished by switch and IR + protected boolean isFinished () + { + return Robot.rollerGripper.getSwitchGamePiece(); + } } diff --git a/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java new file mode 100644 index 0000000..f7e1c78 --- /dev/null +++ b/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java @@ -0,0 +1,20 @@ +package org.usfirst.frc.team3316.robot.sequences; + +import org.usfirst.frc.team3316.robot.stacker.commands.AddGamePieceToStack; +import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToFloor; +import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToTote; + +import edu.wpi.first.wpilibj.command.CommandGroup; + +/** + * + */ +public class AddGamePieceSequence extends CommandGroup +{ + public AddGamePieceSequence() + { + addSequential(new MoveStackerToFloor()); + addSequential(new AddGamePieceToStack()); + addSequential(new MoveStackerToTote()); + } +} diff --git a/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java new file mode 100644 index 0000000..f17f047 --- /dev/null +++ b/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java @@ -0,0 +1,37 @@ +package org.usfirst.frc.team3316.robot.sequences; + +import org.usfirst.frc.team3316.robot.Robot; +import org.usfirst.frc.team3316.robot.config.Config; +import org.usfirst.frc.team3316.robot.logger.DBugLogger; +import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollIn; +import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToFloor; +import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToTote; + +import edu.wpi.first.wpilibj.command.CommandGroup; + +/** + * + */ +public class PickupSequence extends CommandGroup +{ + DBugLogger logger = Robot.logger; + Config config = Robot.config; + + AddGamePieceSequence addGamePieceSequence; + + public PickupSequence () + { + addSequential(new MoveStackerToTote()); + addSequential(new RollIn()); + + addGamePieceSequence = new AddGamePieceSequence(); + } + + protected void end () + { + if (!Robot.stacker.isFull() && Robot.rollerGripper.getSwitchGamePiece()) + { + addGamePieceSequence.start(); + } + } +} diff --git a/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java index f1373d5..f17f047 100644 --- a/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java +++ b/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java @@ -12,23 +12,26 @@ /** * */ -public class pickupSequence extends CommandGroup +public class PickupSequence extends CommandGroup { DBugLogger logger = Robot.logger; Config config = Robot.config; - protected void initialize() + AddGamePieceSequence addGamePieceSequence; + + public PickupSequence () + { + addSequential(new MoveStackerToTote()); + addSequential(new RollIn()); + + addGamePieceSequence = new AddGamePieceSequence(); + } + + protected void end () { - if (Robot.stacker.isFull()) + if (!Robot.stacker.isFull() && Robot.rollerGripper.getSwitchGamePiece()) { - this.cancel(); + addGamePieceSequence.start(); } } - public pickupSequence() - { - addSequential(new MoveStackerToTote()); //makes sure the new gamepiece can enter - addSequential(new RollIn()); - addSequential(new MoveStackerToFloor()); - addSequential(new MoveStackerToTote()); - } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/GamePieceType.java b/src/org/usfirst/frc/team3316/robot/stacker/GamePieceType.java index 1e937f2..64af068 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/GamePieceType.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/GamePieceType.java @@ -3,5 +3,5 @@ public enum GamePieceType { - Container, GreyTote, YellowTote; + Container, Tote; } \ No newline at end of file diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/AddGamePieceToStack.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/AddGamePieceToStack.java new file mode 100644 index 0000000..b640081 --- /dev/null +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/AddGamePieceToStack.java @@ -0,0 +1,40 @@ +package org.usfirst.frc.team3316.robot.stacker.commands; + +import org.usfirst.frc.team3316.robot.Robot; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; +import org.usfirst.frc.team3316.robot.stacker.GamePiece; +import org.usfirst.frc.team3316.robot.stacker.GamePieceType; + +import edu.wpi.first.wpilibj.command.Command; + +/** + * + */ +public class AddGamePieceToStack extends Command +{ + public AddGamePieceToStack() {} + + protected void initialize() + { + GamePieceCollected gpCollected = Robot.rollerGripper.getGamePieceCollected(); + if (gpCollected == GamePieceCollected.Container) + { + Robot.stacker.pushToStack(new GamePiece(GamePieceType.Container)); + } + else if (gpCollected == GamePieceCollected.Tote) + { + Robot.stacker.pushToStack(new GamePiece(GamePieceType.Tote)); + } + } + + protected void execute() {} + + protected boolean isFinished() + { + return true; + } + + protected void end() {} + + protected void interrupted() {} +} diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java index 37007f6..d62cca9 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java @@ -15,15 +15,9 @@ public abstract class MoveStacker extends Command DBugLogger logger = Robot.logger; Config config = Robot.config; - protected double heightMin, heightMax; - - String heightMaxName = "", heightMinName = ""; - - public MoveStacker(String heightMaxName, String heightMinName) + public MoveStacker() { requires(Robot.stacker); - this.heightMaxName = heightMaxName; - this.heightMinName = heightMinName; } protected void initialize() @@ -36,11 +30,6 @@ protected void execute() {} protected boolean isFinished() { return true; - /* - updateHeightRange(); - double currentHeight = Robot.stacker.getHeight(); - return (currentHeight > heightMin) && (currentHeight < heightMax); - */ } protected void end() {} @@ -48,17 +37,4 @@ protected void end() {} protected void interrupted() {} protected abstract void setSolenoids(); - - protected void updateHeightRange () - { - try - { - heightMax = (double) config.get(heightMaxName); - heightMin = (double) config.get(heightMinName); - } - catch (ConfigException e) - { - logger.severe(e); - } - } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java index 4744a66..2eb2343 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java @@ -2,6 +2,7 @@ import org.usfirst.frc.team3316.robot.Robot; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; /** * @@ -9,23 +10,18 @@ public class MoveStackerToFloor extends MoveStacker { double gpDistanceMin, gpDistanceMax; - - public MoveStackerToFloor() - { - super("STACKER_MOVE_STACKER_TO_FLOOR_HEIGHT_MAX", - "STACKER_MOVE_STACKER_TO_FLOOR_HEIGHT_MIN"); - } protected void setSolenoids() { - Robot.stacker.openSolenoidGripper(); //This line is strategically problematic and should be solved - //need to insert condition 'only if there is no gp below the stack' + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.None) + { + Robot.stacker.openSolenoidGripper(); + } Robot.stacker.closeSolenoidContainer(); Robot.stacker.openSolenoidUpper(); Robot.stacker.openSolenoidBottom(); } - //TODO: implement this method in setSolenoids() private void updateDistanceRange () { try diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java index b014f29..6a566e3 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java @@ -10,8 +10,7 @@ public class MoveStackerToTote extends MoveStacker { public MoveStackerToTote() { - super("STACKER_MOVE_STACKER_TO_TOTE_HEIGHT_MAX", - "STACKER_MOVE_STACKER_TO_TOTE_HEIGHT_MIN"); + super(); } protected void initialize() diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java b/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java index 9e30569..fee1d78 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java @@ -4,6 +4,7 @@ import org.usfirst.frc.team3316.robot.config.Config; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; import org.usfirst.frc.team3316.robot.logger.DBugLogger; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.rollerGripper.commands.Roll; import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollJoystick; @@ -29,6 +30,14 @@ public class RollerGripper extends Subsystem private double leftScale, rightScale; + // Variables for getGamePieceCollected() + // They are set in updateDistanceVariables() + private double toteDistanceMin, + toteDistanceMax, + containerDistanceMin, + containerDistanceMax, + gpDistanceThreshold; + private Roll defaultRoll; public RollerGripper () @@ -55,6 +64,75 @@ public boolean set (double speedLeft, double speedRight) return true; } + //TODO: fix name to be getIRGPDistance + public double getGPIRDistance () + { + return (1 / gripperGPIR.getVoltage()); + } + + public boolean getSwitchGamePiece () + { + return !gripperSwitchGP.get(); + } + + /** + * Returns which gamepiece there is in the roller gripper (if any) + * @return Tote for tote, Container for container, Unsure if there + * is something in but can't figure out which and none if empty + */ + public GamePieceCollected getGamePieceCollected () + { + updateDistanceVariables(); + + double gpDistance = getGPIRDistance(); + boolean gpSwitch = getSwitchGamePiece(); + + if (gpSwitch) + { + if (gpDistance > toteDistanceMin && gpDistance < toteDistanceMax) + { + return GamePieceCollected.Tote; + } + else if (gpDistance > containerDistanceMin && gpDistance < containerDistanceMax) + { + return GamePieceCollected.Container; + } + else + { + return GamePieceCollected.Unsure; + } + } + else + { + if (gpDistance < gpDistanceThreshold) + { + return GamePieceCollected.Unsure; + } + else + { + return GamePieceCollected.None; + } + } + } + + private void updateDistanceVariables () + { + try + { + toteDistanceMin = (double) config.get("rollerGripper_ToteDistanceMinimum"); + toteDistanceMax = (double) config.get("rollerGripper_ToteDistanceMaximum"); + + containerDistanceMin = (double) config.get("rollerGripper_ContainerDistanceMinimum"); + containerDistanceMax = (double) config.get("rollerGripper_ContainerDistanceMaximum"); + + gpDistanceThreshold = (double) config.get("rollerGripper_GamePieceDistanceThreshold"); + } + catch (ConfigException e) + { + logger.severe(e); + } + } + private void updateScales () { try @@ -68,17 +146,6 @@ private void updateScales () } } - //TODO: fix name to be getIRGPDistance - public double getGPIRDistance () - { - return (1 / gripperGPIR.getVoltage()); - } - - public boolean getSwitchGP () - { - return gripperSwitchGP.get(); - } - private void printTheTruth() { System.out.println("Vita is the Melech!!"); From 613ab7466f75f66e859b8fe5c6d6826e2d00371e Mon Sep 17 00:00:00 2001 From: frc3316 Date: Sat, 14 Feb 2015 13:56:57 +0200 Subject: [PATCH 16/29] Finished adding PickupSequence and fixed MoveStacker commmands --- .../frc/team3316/robot/config/Config.java | 226 ++++++++++++++++++ .../robot/rollerGripper/commands/RollOut.java | 7 + .../robot/sequences/AddGamePieceSequence.java | 2 +- .../robot/sequences/PickupSequence.java | 37 --- .../robot/sequences/pickupSequence.java | 37 --- .../robot/stacker/StackerPosition.java | 2 +- .../stacker/commands/MoveStackerToFloor.java | 13 +- .../stacker/commands/MoveStackerToStep.java | 30 ++- .../stacker/commands/MoveStackerToTote.java | 18 +- .../team3316/robot/subsystems/Stacker.java | 53 +++- 10 files changed, 314 insertions(+), 111 deletions(-) delete mode 100644 src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java delete mode 100644 src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java diff --git a/src/org/usfirst/frc/team3316/robot/config/Config.java b/src/org/usfirst/frc/team3316/robot/config/Config.java index 12ade18..fccdcdb 100644 --- a/src/org/usfirst/frc/team3316/robot/config/Config.java +++ b/src/org/usfirst/frc/team3316/robot/config/Config.java @@ -121,6 +121,7 @@ private void addToVariables (String key, Object value) @SuppressWarnings("unchecked") private void deserializationInit () { +<<<<<<< HEAD String configPath; if (robotA) @@ -162,5 +163,230 @@ private void deserializationInit () { logger.severe(e); } +======= + /* + * Human IO + */ + /* + * Constants + */ + addToConstants("JOYSTICK_LEFT", 0); + addToConstants("JOYSTICK_RIGHT", 1); + addToConstants("JOYSTICK_OPERATOR", 2); + + //subsystem + /* + * Stacker + */ + addToConstants("BUTTON_MOVE_STACKER_TO_FLOOR", 1); + addToConstants("BUTTON_MOVE_STACKER_TO_STEP", 2); + addToConstants("BUTTON_MOVE_STACKER_TO_TOTE", 4); + + addToConstants("BUTTON_HOLD_CONTAINER", 10); + addToConstants("BUTTON_RELEASE_CONTAINER", 9); + + addToConstants("BUTTON_OPEN_GRIPPER", 5); + addToConstants("BUTTON_CLOSE_GRIPPER", 6); + + /* + * Roller-Gripper + */ + addToConstants("BUTTON_ROLL_IN", 180); + addToConstants("BUTTON_ROLL_OUT", 0); + addToConstants("BUTTON_ROLL_TURN_CLOCKWISE", 90); + addToConstants("BUTTON_ROLL_TURN_COUNTER_CLOCKWISE", 270); + + /* + * Anschluss + */ + addToConstants("BUTTON_OPEN_ANSCHLUSS", 8); + addToConstants("BUTTON_CLOSE_ANSCHLUSS", 7); + /* + * Chassis + */ + /* + * Constants + */ + addToConstants("CHASSIS_MOTOR_CONTROLLER_LEFT_1", 6); + addToConstants("CHASSIS_MOTOR_CONTROLLER_LEFT_2", 7); + + addToConstants("CHASSIS_MOTOR_CONTROLLER_RIGHT_1", 1); + addToConstants("CHASSIS_MOTOR_CONTROLLER_RIGHT_2", 2); + + addToConstants("CHASSIS_MOTOR_CONTROLLER_CENTER_1", 0); + addToConstants("CHASSIS_MOTOR_CONTROLLER_CENTER_2", 5); + + addToConstants("CHASSIS_ENCODER_LEFT_A", 4); + addToConstants("CHASSIS_ENCODER_LEFT_B", 5); + + addToConstants("CHASSIS_ENCODER_RIGHT_A", 2); + addToConstants("CHASSIS_ENCODER_RIGHT_B", 3); + + addToConstants("CHASSIS_ENCODER_CENTER_A", 0); + addToConstants("CHASSIS_ENCODER_CENTER_B", 1); + + addToConstants("CHASSIS_ENCODER_LEFT_DISTANCE_PER_PULSE", -0.0018702293765902); + addToConstants("CHASSIS_ENCODER_RIGHT_DISTANCE_PER_PULSE", 0.0018702293765902); + addToConstants("CHASSIS_ENCODER_CENTER_DISTANCE_PER_PULSE", 0.0012468195843934); + + addToConstants("CHASSIS_WIDTH", 0.5322); //in meters + /* + * Variables + */ + + //Subsystem + addToVariables("chassis_LeftScale", 1.0); + addToVariables("chassis_RightScale", -1.0); + addToVariables("chassis_CenterScale", 1.0); + + addToVariables("chassis_HeadingToSet", 0.0); // This is the heading that the SetHeadingSDB command sets to + // It is configurable in the SDB (it should appear in initSDB()) + //TankDrive + addToVariables("chassis_TankDrive_InvertX", false); + addToVariables("chassis_TankDrive_InvertY", true); + + addToVariables("chassis_TankDrive_LowPass", 0.0); + //RobotOrientedDrive + addToVariables("chassis_RobotOrientedDrive_TurnScale", 1.0); + + //RobotOrientedNavigation + addToVariables("chassis_RobotOrientedNavigation_PIDControllerX_KP", 0.0); + addToVariables("chassis_RobotOrientedNavigation_PIDControllerX_KI", 0.0); + addToVariables("chassis_RobotOrientedNavigation_PIDControllerX_KD", 0.0); + + addToVariables("chassis_RobotOrientedNavigation_PIDControllerY_KP", 0.0); + addToVariables("chassis_RobotOrientedNavigation_PIDControllerY_KI", 0.0); + addToVariables("chassis_RobotOrientedNavigation_PIDControllerY_KD", 0.0); + + addToVariables("chassis_RobotOrientedNavigation_PIDControllerHeading_KP", 0.0); + addToVariables("chassis_RobotOrientedNavigation_PIDControllerHeading_KI", 0.0); + addToVariables("chassis_RobotOrientedNavigation_PIDControllerHeading_KD", 0.0); + + addToVariables("chassis_RobotOrientedNavigation_PIDControllerX_AbsoluteTolerance", 0.0); + addToVariables("chassis_RobotOrientedNavigation_PIDControllerY_AbsoluteTolerance", 0.0); + addToVariables("chassis_RobotOrientedNavigation_PIDControllerHeading_AbsoluteTolerance", 0.0); + + addToVariables("chassis_RobotOrientedNavigation_PIDControllerX_MinimumOutput", -1.0); + addToVariables("chassis_RobotOrientedNavigation_PIDControllerX_MaximumOutput", 1.0); + + addToVariables("chassis_RobotOrientedNavigation_PIDControllerY_MinimumOutput", -1.0); + addToVariables("chassis_RobotOrientedNavigation_PIDControllerY_MaximumOutput", 1.0); + + addToVariables("chassis_RobotOrientedNavigation_PIDControllerHeading_MinimumOutput", -1.0); + addToVariables("chassis_RobotOrientedNavigation_PIDControllerHeading_MaximumOutput", 1.0); + /* + * Anschluss + */ + /* + * Constants + */ + addToConstants("ANSCHLUSS_MOTOR_CONTROLLER", 4); + + addToConstants("ANSCHLUSS_DIGITAL_INPUT_CLOSED", 11); + addToConstants("ANSCHLUSS_DIGITAL_INPUT_OPENED", 10); + + + + /* + * Variables + */ + addToVariables("anschluss_CloseAnschluss_MotorSpeed", -1.0); + addToVariables("anschluss_OpenAnschluss_MotorSpeed", 1.0); + /* + * Roller Gripper + */ + + /* + * Constants + */ + addToConstants("ROLLER_GRIPPER_GAME_PIECE_IR", 1); + addToConstants("ROLLER_GRIPPER_SWITCH_GAME_PIECE", 7); + + addToConstants("ROLLER_GRIPPER_MOTOR_CONTROLLER_LEFT", 8); + addToConstants("ROLLER_GRIPPER_MOTOR_CONTROLLER_RIGHT", 3); + + /* + * Variables + */ + //Subsystem + addToVariables("rollerGripper_LeftScale", 1.0); + addToVariables("rollerGripper_RightScale", -1.0); + + addToVariables("rollerGripper_ToteDistanceMinimum", 0.325); + addToVariables("rollerGripper_ToteDistanceMaximum", 0.34); + + addToVariables("rollerGripper_ContainerDistanceMinimum", 0.39); + addToVariables("rollerGripper_ContainerDistanceMaximum", 0.41); + + addToVariables("rollerGripper_GamePieceDistanceThreshold", 1.0); + + //RollIn + addToVariables("rollerGripper_RollIn_SpeedLeft", 1.0); + addToVariables("rollerGripper_RollIn_SpeedRight", 1.0); + + //RollOut + addToVariables("rollerGripper_RollOut_SpeedLeft", -1.0); + addToVariables("rollerGripper_RollOut_SpeedRight", -1.0); + + //RollTurnClockwise + addToVariables("rollerGripper_RollTurnClockwise_SpeedLeft", -1.0); + addToVariables("rollerGripper_RollTurnClockwise_SpeedRight", 1.0); + + //RollTurnCounterClockwise + addToVariables("rollerGripper_RollTurnCounterClockwise_SpeedLeft", 1.0); + addToVariables("rollerGripper_RollTurnCounterClockwise_SpeedRight", -1.0); + + //RollJoystick + addToVariables("rollerGripper_RollJoystick_ChannelX", 0); + addToVariables("rollerGripper_RollJoystick_ChannelY", 1); + + addToVariables("rollerGripper_RollJoystick_InvertX", true); + addToVariables("rollerGripper_RollJoystick_InvertY", false); + + addToVariables("rollerGripper_RollJoystick_LowPass", 0.15); + + /* + * Stacker + */ + /* + * Constants + */ + //Subsystem + addToConstants("STACKER_SOLENOID_UPPER_FORWARD", 6); + addToConstants("STACKER_SOLENOID_UPPER_REVERSE", 7); + + addToConstants("STACKER_SOLENOID_BOTTOM_FORWARD", 4); + addToConstants("STACKER_SOLENOID_BOTTOM_REVERSE", 5); + + addToConstants("STACKER_SOLENOID_CONTAINER_FORWARD", 3); + addToConstants("STACKER_SOLENOID_CONTAINER_REVERSE", 2); + + addToConstants("STACKER_SOLENOID_GRIPPER_FORWARD", 0); + addToConstants("STACKER_SOLENOID_GRIPPER_REVERSE", 1); + + addToConstants("STACKER_IR", 0); + + + addToConstants("SWITCH_RATCHET_LEFT", 7); + addToConstants("SWITCH_RATCHET_RIGHT", 8); + + /* + * Variables + */ + //Subsystem + + //TODO: re-determine these values + addToVariables("stacker_HeightFloorMinimum", 0.4); + addToVariables("stacker_HeightFloorMaximum", 0.42); + + addToVariables("stacker_HeightToteMinimum", 1.45); + addToVariables("stacker_HeightToteMaximum", 1.62); + + addToVariables("stacker_HeightStepMinimum", 0.95); + addToVariables("stacker_HeightStepMaximum", 1.05); + + addToVariables("stacker_HeightStuckOnContainerMinimum", 1.05); + addToVariables("stacker_HeightStuckOnContainerMaximum", 1.05); +>>>>>>> Finished adding PickupSequence and fixed MoveStacker commmands } } diff --git a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java index 2952d45..d63ec41 100644 --- a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java +++ b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java @@ -1,6 +1,8 @@ package org.usfirst.frc.team3316.robot.rollerGripper.commands; +import org.usfirst.frc.team3316.robot.Robot; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; public class RollOut extends Roll { @@ -16,4 +18,9 @@ protected void setSpeeds () logger.severe(e); } } + + protected boolean isFinished () + { + return Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.None; + } } diff --git a/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java index f7e1c78..2b6fb26 100644 --- a/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java +++ b/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java @@ -13,8 +13,8 @@ public class AddGamePieceSequence extends CommandGroup { public AddGamePieceSequence() { + addSequential(new AddGamePieceToStack()); addSequential(new MoveStackerToFloor()); - addSequential(new AddGamePieceToStack()); addSequential(new MoveStackerToTote()); } } diff --git a/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java deleted file mode 100644 index f17f047..0000000 --- a/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java +++ /dev/null @@ -1,37 +0,0 @@ -package org.usfirst.frc.team3316.robot.sequences; - -import org.usfirst.frc.team3316.robot.Robot; -import org.usfirst.frc.team3316.robot.config.Config; -import org.usfirst.frc.team3316.robot.logger.DBugLogger; -import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollIn; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToFloor; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToTote; - -import edu.wpi.first.wpilibj.command.CommandGroup; - -/** - * - */ -public class PickupSequence extends CommandGroup -{ - DBugLogger logger = Robot.logger; - Config config = Robot.config; - - AddGamePieceSequence addGamePieceSequence; - - public PickupSequence () - { - addSequential(new MoveStackerToTote()); - addSequential(new RollIn()); - - addGamePieceSequence = new AddGamePieceSequence(); - } - - protected void end () - { - if (!Robot.stacker.isFull() && Robot.rollerGripper.getSwitchGamePiece()) - { - addGamePieceSequence.start(); - } - } -} diff --git a/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java deleted file mode 100644 index f17f047..0000000 --- a/src/org/usfirst/frc/team3316/robot/sequences/pickupSequence.java +++ /dev/null @@ -1,37 +0,0 @@ -package org.usfirst.frc.team3316.robot.sequences; - -import org.usfirst.frc.team3316.robot.Robot; -import org.usfirst.frc.team3316.robot.config.Config; -import org.usfirst.frc.team3316.robot.logger.DBugLogger; -import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollIn; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToFloor; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToTote; - -import edu.wpi.first.wpilibj.command.CommandGroup; - -/** - * - */ -public class PickupSequence extends CommandGroup -{ - DBugLogger logger = Robot.logger; - Config config = Robot.config; - - AddGamePieceSequence addGamePieceSequence; - - public PickupSequence () - { - addSequential(new MoveStackerToTote()); - addSequential(new RollIn()); - - addGamePieceSequence = new AddGamePieceSequence(); - } - - protected void end () - { - if (!Robot.stacker.isFull() && Robot.rollerGripper.getSwitchGamePiece()) - { - addGamePieceSequence.start(); - } - } -} diff --git a/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java b/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java index e7867c1..4ae1df1 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java @@ -2,5 +2,5 @@ public enum StackerPosition { - Tote, Step, Floor; + Tote, Step, Floor, StuckOnContainer; } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java index 2eb2343..98bad13 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java @@ -3,13 +3,13 @@ import org.usfirst.frc.team3316.robot.Robot; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; +import org.usfirst.frc.team3316.robot.stacker.StackerPosition; /** * */ public class MoveStackerToFloor extends MoveStacker { - double gpDistanceMin, gpDistanceMax; protected void setSolenoids() { @@ -22,16 +22,15 @@ protected void setSolenoids() Robot.stacker.openSolenoidBottom(); } - private void updateDistanceRange () + protected boolean isFinished () { - try + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) { - gpDistanceMax = (double) config.get("stacker_MoveStackerToFloor_GPDistanceMax"); - gpDistanceMin = (double) config.get("stacker_MoveStackerToFloor_GPDistanceMin"); + return (Robot.stacker.getPosition() == StackerPosition.StuckOnContainer); } - catch (ConfigException e) + else { - logger.severe(e); + return (Robot.stacker.getPosition() == StackerPosition.Floor); } } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java index 744b3c2..86a289c 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java @@ -1,28 +1,19 @@ package org.usfirst.frc.team3316.robot.stacker.commands; import org.usfirst.frc.team3316.robot.Robot; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.stacker.StackerPosition; import edu.wpi.first.wpilibj.DoubleSolenoid; -/** - * - */ public class MoveStackerToStep extends MoveStacker { - public MoveStackerToStep() - { - super("STACKER_MOVE_STACKER_TO_STEP_HEIGHT_MAX", - "STACKER_MOVE_STACKER_TO_STEP_HEIGHT_MIN"); - } - protected void initialize() { /* * If one of the ratchets is not in place and they should be pressed, dont start */ - if ( Robot.stacker.getSolenoidContainer() == DoubleSolenoid.Value.kReverse && - Robot.stacker.getPosition() == StackerPosition.Floor && + if ( Robot.stacker.getPosition() == StackerPosition.Floor && (!Robot.stacker.getSwitchLeft() || !Robot.stacker.getSwitchRight())) { this.cancel(); @@ -39,7 +30,24 @@ protected void setSolenoids() { Robot.stacker.openSolenoidGripper(); } + //TODO: check if the condition should be if the command started when the stacker was stuck on a container + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) + { + Robot.stacker.openSolenoidContainer(); + } Robot.stacker.closeSolenoidUpper(); Robot.stacker.openSolenoidBottom(); } + + protected boolean isFinished () + { + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) + { + return (Robot.stacker.getPosition() == StackerPosition.StuckOnContainer); + } + else + { + return (Robot.stacker.getPosition() == StackerPosition.Step); + } + } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java index 6a566e3..a8ef7e6 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java @@ -1,6 +1,7 @@ package org.usfirst.frc.team3316.robot.stacker.commands; import org.usfirst.frc.team3316.robot.Robot; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.stacker.GamePieceType; import org.usfirst.frc.team3316.robot.stacker.StackerPosition; @@ -8,18 +9,12 @@ public class MoveStackerToTote extends MoveStacker { - public MoveStackerToTote() - { - super(); - } - protected void initialize() { /* * If one of the ratchets is not in place and they should be pressed, dont start */ - if ( Robot.stacker.getSolenoidContainer() == DoubleSolenoid.Value.kReverse && - Robot.stacker.getPosition() == StackerPosition.Floor && + if ( Robot.stacker.getPosition() == StackerPosition.Floor && (!Robot.stacker.getSwitchLeft() || !Robot.stacker.getSwitchRight())) { this.cancel(); @@ -32,12 +27,17 @@ protected void initialize() protected void setSolenoids() { - if ( Robot.stacker.getStackBase() != null && - Robot.stacker.getStackBase().getType() == GamePieceType.Container) + //TODO: check if the condition should be if the command started when the stacker was stuck on a container + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) { Robot.stacker.openSolenoidContainer(); } Robot.stacker.closeSolenoidUpper(); Robot.stacker.closeSolenoidBottom(); } + + protected boolean isFinished () + { + return (Robot.stacker.getPosition() == StackerPosition.Tote); + } } diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java index ec1b36d..fcdbe36 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java @@ -32,6 +32,11 @@ public class Stacker extends Subsystem private AnalogInput heightIR; //infrared private DigitalInput switchRight, switchLeft; //the switches that signify if there's a tote or a container in the stacker + private double heightFloorMin, heightFloorMax, + heightStepMin, heightStepMax, + heightToteMin, heightToteMax, + heightStuckOnContainerMin, heightStuckOnContainerMax; + private Stack stack; public Stacker () @@ -125,25 +130,57 @@ public boolean getSwitchLeft () return switchLeft.get(); } + /* + * TODO: check if StuckOnContainer is necessary (if it's not simply step or floor) + */ public StackerPosition getPosition () { - /* - * TODO: this method should return a position based on the stacker IR - */ - if (solenoidUpper.get() == DoubleSolenoid.Value.kForward && - solenoidBottom.get() == DoubleSolenoid.Value.kForward) + updateHeights(); + + double height = getHeight(); + + if ((height > heightFloorMin) && (height < heightFloorMax)) { return StackerPosition.Floor; } - else if (solenoidUpper.get() == DoubleSolenoid.Value.kReverse && - solenoidBottom.get() == DoubleSolenoid.Value.kReverse) + else if ((height > heightToteMin) && (height < heightToteMax)) { return StackerPosition.Tote; } - else + else if ((height > heightStepMin) && (height < heightStepMax)) { return StackerPosition.Step; } + else if ((height > heightStuckOnContainerMin) && (height < heightStuckOnContainerMax)) + { + return StackerPosition.StuckOnContainer; + } + else + { + return null; + } + } + + private void updateHeights () + { + try + { + heightFloorMin = (double) config.get("stacker_HeightFloorMinimum"); + heightFloorMax = (double) config.get("stacker_HeightFloorMaximum"); + + heightToteMin = (double) config.get("stacker_HeightToteMinimum"); + heightToteMax = (double) config.get("stacker_HeightToteMaximum"); + + heightStepMin = (double) config.get("stacker_HeightStepMinimum"); + heightStepMax = (double) config.get("stacker_HeightStepMaximum"); + + heightStuckOnContainerMin = (double) config.get("stacker_HeightStuckOnContainerMinimum"); + heightStuckOnContainerMax = (double) config.get("stacker_HeightStuckOnContainerMaximum"); + } + catch (ConfigException e) + { + logger.severe(e); + } } public DoubleSolenoid.Value getSolenoidContainer () From cd9169e2afe18e5fcd547ce98039924dd7622784 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Sat, 14 Feb 2015 13:56:57 +0200 Subject: [PATCH 17/29] Finished adding PickupSequence and fixed MoveStacker commmands --- .../frc/team3316/robot/config/Config.java | 226 ------------------ .../frc/team3316/robot/humanIO/SDB.java | 15 ++ .../stacker/commands/MoveStackerToStep.java | 2 - 3 files changed, 15 insertions(+), 228 deletions(-) diff --git a/src/org/usfirst/frc/team3316/robot/config/Config.java b/src/org/usfirst/frc/team3316/robot/config/Config.java index fccdcdb..12ade18 100644 --- a/src/org/usfirst/frc/team3316/robot/config/Config.java +++ b/src/org/usfirst/frc/team3316/robot/config/Config.java @@ -121,7 +121,6 @@ private void addToVariables (String key, Object value) @SuppressWarnings("unchecked") private void deserializationInit () { -<<<<<<< HEAD String configPath; if (robotA) @@ -163,230 +162,5 @@ private void deserializationInit () { logger.severe(e); } -======= - /* - * Human IO - */ - /* - * Constants - */ - addToConstants("JOYSTICK_LEFT", 0); - addToConstants("JOYSTICK_RIGHT", 1); - addToConstants("JOYSTICK_OPERATOR", 2); - - //subsystem - /* - * Stacker - */ - addToConstants("BUTTON_MOVE_STACKER_TO_FLOOR", 1); - addToConstants("BUTTON_MOVE_STACKER_TO_STEP", 2); - addToConstants("BUTTON_MOVE_STACKER_TO_TOTE", 4); - - addToConstants("BUTTON_HOLD_CONTAINER", 10); - addToConstants("BUTTON_RELEASE_CONTAINER", 9); - - addToConstants("BUTTON_OPEN_GRIPPER", 5); - addToConstants("BUTTON_CLOSE_GRIPPER", 6); - - /* - * Roller-Gripper - */ - addToConstants("BUTTON_ROLL_IN", 180); - addToConstants("BUTTON_ROLL_OUT", 0); - addToConstants("BUTTON_ROLL_TURN_CLOCKWISE", 90); - addToConstants("BUTTON_ROLL_TURN_COUNTER_CLOCKWISE", 270); - - /* - * Anschluss - */ - addToConstants("BUTTON_OPEN_ANSCHLUSS", 8); - addToConstants("BUTTON_CLOSE_ANSCHLUSS", 7); - /* - * Chassis - */ - /* - * Constants - */ - addToConstants("CHASSIS_MOTOR_CONTROLLER_LEFT_1", 6); - addToConstants("CHASSIS_MOTOR_CONTROLLER_LEFT_2", 7); - - addToConstants("CHASSIS_MOTOR_CONTROLLER_RIGHT_1", 1); - addToConstants("CHASSIS_MOTOR_CONTROLLER_RIGHT_2", 2); - - addToConstants("CHASSIS_MOTOR_CONTROLLER_CENTER_1", 0); - addToConstants("CHASSIS_MOTOR_CONTROLLER_CENTER_2", 5); - - addToConstants("CHASSIS_ENCODER_LEFT_A", 4); - addToConstants("CHASSIS_ENCODER_LEFT_B", 5); - - addToConstants("CHASSIS_ENCODER_RIGHT_A", 2); - addToConstants("CHASSIS_ENCODER_RIGHT_B", 3); - - addToConstants("CHASSIS_ENCODER_CENTER_A", 0); - addToConstants("CHASSIS_ENCODER_CENTER_B", 1); - - addToConstants("CHASSIS_ENCODER_LEFT_DISTANCE_PER_PULSE", -0.0018702293765902); - addToConstants("CHASSIS_ENCODER_RIGHT_DISTANCE_PER_PULSE", 0.0018702293765902); - addToConstants("CHASSIS_ENCODER_CENTER_DISTANCE_PER_PULSE", 0.0012468195843934); - - addToConstants("CHASSIS_WIDTH", 0.5322); //in meters - /* - * Variables - */ - - //Subsystem - addToVariables("chassis_LeftScale", 1.0); - addToVariables("chassis_RightScale", -1.0); - addToVariables("chassis_CenterScale", 1.0); - - addToVariables("chassis_HeadingToSet", 0.0); // This is the heading that the SetHeadingSDB command sets to - // It is configurable in the SDB (it should appear in initSDB()) - //TankDrive - addToVariables("chassis_TankDrive_InvertX", false); - addToVariables("chassis_TankDrive_InvertY", true); - - addToVariables("chassis_TankDrive_LowPass", 0.0); - //RobotOrientedDrive - addToVariables("chassis_RobotOrientedDrive_TurnScale", 1.0); - - //RobotOrientedNavigation - addToVariables("chassis_RobotOrientedNavigation_PIDControllerX_KP", 0.0); - addToVariables("chassis_RobotOrientedNavigation_PIDControllerX_KI", 0.0); - addToVariables("chassis_RobotOrientedNavigation_PIDControllerX_KD", 0.0); - - addToVariables("chassis_RobotOrientedNavigation_PIDControllerY_KP", 0.0); - addToVariables("chassis_RobotOrientedNavigation_PIDControllerY_KI", 0.0); - addToVariables("chassis_RobotOrientedNavigation_PIDControllerY_KD", 0.0); - - addToVariables("chassis_RobotOrientedNavigation_PIDControllerHeading_KP", 0.0); - addToVariables("chassis_RobotOrientedNavigation_PIDControllerHeading_KI", 0.0); - addToVariables("chassis_RobotOrientedNavigation_PIDControllerHeading_KD", 0.0); - - addToVariables("chassis_RobotOrientedNavigation_PIDControllerX_AbsoluteTolerance", 0.0); - addToVariables("chassis_RobotOrientedNavigation_PIDControllerY_AbsoluteTolerance", 0.0); - addToVariables("chassis_RobotOrientedNavigation_PIDControllerHeading_AbsoluteTolerance", 0.0); - - addToVariables("chassis_RobotOrientedNavigation_PIDControllerX_MinimumOutput", -1.0); - addToVariables("chassis_RobotOrientedNavigation_PIDControllerX_MaximumOutput", 1.0); - - addToVariables("chassis_RobotOrientedNavigation_PIDControllerY_MinimumOutput", -1.0); - addToVariables("chassis_RobotOrientedNavigation_PIDControllerY_MaximumOutput", 1.0); - - addToVariables("chassis_RobotOrientedNavigation_PIDControllerHeading_MinimumOutput", -1.0); - addToVariables("chassis_RobotOrientedNavigation_PIDControllerHeading_MaximumOutput", 1.0); - /* - * Anschluss - */ - /* - * Constants - */ - addToConstants("ANSCHLUSS_MOTOR_CONTROLLER", 4); - - addToConstants("ANSCHLUSS_DIGITAL_INPUT_CLOSED", 11); - addToConstants("ANSCHLUSS_DIGITAL_INPUT_OPENED", 10); - - - - /* - * Variables - */ - addToVariables("anschluss_CloseAnschluss_MotorSpeed", -1.0); - addToVariables("anschluss_OpenAnschluss_MotorSpeed", 1.0); - /* - * Roller Gripper - */ - - /* - * Constants - */ - addToConstants("ROLLER_GRIPPER_GAME_PIECE_IR", 1); - addToConstants("ROLLER_GRIPPER_SWITCH_GAME_PIECE", 7); - - addToConstants("ROLLER_GRIPPER_MOTOR_CONTROLLER_LEFT", 8); - addToConstants("ROLLER_GRIPPER_MOTOR_CONTROLLER_RIGHT", 3); - - /* - * Variables - */ - //Subsystem - addToVariables("rollerGripper_LeftScale", 1.0); - addToVariables("rollerGripper_RightScale", -1.0); - - addToVariables("rollerGripper_ToteDistanceMinimum", 0.325); - addToVariables("rollerGripper_ToteDistanceMaximum", 0.34); - - addToVariables("rollerGripper_ContainerDistanceMinimum", 0.39); - addToVariables("rollerGripper_ContainerDistanceMaximum", 0.41); - - addToVariables("rollerGripper_GamePieceDistanceThreshold", 1.0); - - //RollIn - addToVariables("rollerGripper_RollIn_SpeedLeft", 1.0); - addToVariables("rollerGripper_RollIn_SpeedRight", 1.0); - - //RollOut - addToVariables("rollerGripper_RollOut_SpeedLeft", -1.0); - addToVariables("rollerGripper_RollOut_SpeedRight", -1.0); - - //RollTurnClockwise - addToVariables("rollerGripper_RollTurnClockwise_SpeedLeft", -1.0); - addToVariables("rollerGripper_RollTurnClockwise_SpeedRight", 1.0); - - //RollTurnCounterClockwise - addToVariables("rollerGripper_RollTurnCounterClockwise_SpeedLeft", 1.0); - addToVariables("rollerGripper_RollTurnCounterClockwise_SpeedRight", -1.0); - - //RollJoystick - addToVariables("rollerGripper_RollJoystick_ChannelX", 0); - addToVariables("rollerGripper_RollJoystick_ChannelY", 1); - - addToVariables("rollerGripper_RollJoystick_InvertX", true); - addToVariables("rollerGripper_RollJoystick_InvertY", false); - - addToVariables("rollerGripper_RollJoystick_LowPass", 0.15); - - /* - * Stacker - */ - /* - * Constants - */ - //Subsystem - addToConstants("STACKER_SOLENOID_UPPER_FORWARD", 6); - addToConstants("STACKER_SOLENOID_UPPER_REVERSE", 7); - - addToConstants("STACKER_SOLENOID_BOTTOM_FORWARD", 4); - addToConstants("STACKER_SOLENOID_BOTTOM_REVERSE", 5); - - addToConstants("STACKER_SOLENOID_CONTAINER_FORWARD", 3); - addToConstants("STACKER_SOLENOID_CONTAINER_REVERSE", 2); - - addToConstants("STACKER_SOLENOID_GRIPPER_FORWARD", 0); - addToConstants("STACKER_SOLENOID_GRIPPER_REVERSE", 1); - - addToConstants("STACKER_IR", 0); - - - addToConstants("SWITCH_RATCHET_LEFT", 7); - addToConstants("SWITCH_RATCHET_RIGHT", 8); - - /* - * Variables - */ - //Subsystem - - //TODO: re-determine these values - addToVariables("stacker_HeightFloorMinimum", 0.4); - addToVariables("stacker_HeightFloorMaximum", 0.42); - - addToVariables("stacker_HeightToteMinimum", 1.45); - addToVariables("stacker_HeightToteMaximum", 1.62); - - addToVariables("stacker_HeightStepMinimum", 0.95); - addToVariables("stacker_HeightStepMaximum", 1.05); - - addToVariables("stacker_HeightStuckOnContainerMinimum", 1.05); - addToVariables("stacker_HeightStuckOnContainerMaximum", 1.05); ->>>>>>> Finished adding PickupSequence and fixed MoveStacker commmands } } diff --git a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java index 2ffbb3a..b37935c 100644 --- a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java +++ b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java @@ -189,5 +189,20 @@ private void initSDB () putConfigVariableInSDB("rollerGripper_RollJoystick_LowPass"); + /* + * Stacker + */ + putConfigVariableInSDB("stacker_HeightFloorMinimum"); + putConfigVariableInSDB("stacker_HeightFloorMaximum"); + + putConfigVariableInSDB("stacker_HeightToteMinimum"); + putConfigVariableInSDB("stacker_HeightToteMaximum"); + + putConfigVariableInSDB("stacker_HeightStepMinimum"); + putConfigVariableInSDB("stacker_HeightStepMaximum"); + + putConfigVariableInSDB("stacker_HeightStuckOnContainerMinimum"); + putConfigVariableInSDB("stacker_HeightStuckOnContainerMaximum"); + } } \ No newline at end of file diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java index 86a289c..7afd479 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java @@ -4,8 +4,6 @@ import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.stacker.StackerPosition; -import edu.wpi.first.wpilibj.DoubleSolenoid; - public class MoveStackerToStep extends MoveStacker { protected void initialize() From 913a77e5ad93a372e93010451410f05e1d39334e Mon Sep 17 00:00:00 2001 From: frc3316 Date: Sat, 14 Feb 2015 14:34:09 +0200 Subject: [PATCH 18/29] Fixed all of the TODO's in the code --- .../frc/team3316/robot/chassis/commands/FieldOrientedDrive.java | 2 -- .../frc/team3316/robot/chassis/commands/RobotOrientedDrive.java | 1 - 2 files changed, 3 deletions(-) diff --git a/src/org/usfirst/frc/team3316/robot/chassis/commands/FieldOrientedDrive.java b/src/org/usfirst/frc/team3316/robot/chassis/commands/FieldOrientedDrive.java index 7030b8f..4ef0e3a 100644 --- a/src/org/usfirst/frc/team3316/robot/chassis/commands/FieldOrientedDrive.java +++ b/src/org/usfirst/frc/team3316/robot/chassis/commands/FieldOrientedDrive.java @@ -19,8 +19,6 @@ protected void setFieldVector (double x, double y) //clockwise is positive and //counter-clockwise is negative double robotAngleRad = Math.toRadians(Robot.chassis.getHeading()); //Robot angle - // For D-Bugging purposes - SmartDashboard.putNumber("Current Heading", Robot.chassis.getHeading()); //TODO: MOVE THIS TO A BETTER PLACE double angleDiff = vectorAngle - robotAngleRad; //The angle of the vector oriented to the robot diff --git a/src/org/usfirst/frc/team3316/robot/chassis/commands/RobotOrientedDrive.java b/src/org/usfirst/frc/team3316/robot/chassis/commands/RobotOrientedDrive.java index e01b69c..a44e417 100644 --- a/src/org/usfirst/frc/team3316/robot/chassis/commands/RobotOrientedDrive.java +++ b/src/org/usfirst/frc/team3316/robot/chassis/commands/RobotOrientedDrive.java @@ -21,7 +21,6 @@ protected void setRobotVector (double x, double y) protected void setRotation (double requiredTurn) { - //TODO: figure out PID rotation //NOTE: Required turn cannot be larger than yIn. /* From 0d79eeb894775a7a13fcf59a09d868aa960c2bc0 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Mon, 16 Feb 2015 18:58:15 +0200 Subject: [PATCH 19/29] Added gamepiece ir variables to sdb for configuration --- dist/FRCUserProgram.jar | Bin 1783351 -> 1785739 bytes .../frc/team3316/robot/humanIO/SDB.java | 9 +++++++++ sysProps.xml | Bin 5950 -> 5950 bytes 3 files changed, 9 insertions(+) diff --git a/dist/FRCUserProgram.jar b/dist/FRCUserProgram.jar index b6cc4a475de6072af137120fd8ad89987f6e6b3e..71fbe8fce66b9688db8bd6db1dcad4cedfd52b41 100644 GIT binary patch delta 37709 zcmZ6yV|ZLq+cq3c)YwjA+qP{tw(U%tq!Zh=ZQHi(#%z-Y&6oCmpZ9z3=g*w`T5HWd zW{!Q~ys%p?>>}Rn5R~O0q2R&5V8Oul65|kPAa)buxE3My5)%-?KmP?LaN5712hQ{X z4UypK;D3=Cvh*L$Lz(|W9_aCZ2!QqehhO2Uk^X*-8HerfadRAhrnKlsWuL!(jNy%NtMS%bR|8)Yrf#TmIegAhZD0a9$9ONp&Fi zZ&7GLJ2VHp4x@Jl;D);b-!dS8E#wFOpIR9Fa%;Wl!pU6q@@DM_sp;(~f|UDCC7r#1 ztXCnYkXu5j(qSjFuv9p!;}PW^FPQtWuSGeFp@)m{}RDTCD)(^a`F-86?Y%} zaN^(3?Qw~Ru^T4KQ=L*8#}*J!rnY9`n{z5PqCmfQGU?`S=sq+yo$^`oF9<3ycw_EC z;ZUKzrb=LkZ6Pc3*~<~H@h?znjKbu%JrJ{7Zza1SWn5oHs|bprx7%oqAjBs=$o{Tm z=T>LC*BvDg_N4A1i2ef(c=4$-+Lx1PH@`pYz2*o=J&*pl6P_rUcPddJh8n#!=iM&` zKC^HI5?iah8S@F7qm(t_lwbo^Q_PL=9kY3LtP{-V_-Ca5=9I&1n!9~IJ$LaxqKR}3 z^y^hShR0X3ZMU1BAu^{Vu-sne4-;tqRgET*1OzLl#!N|p>5s+u(F7$WPT)zqLLshX}mouoRN{^^>to*2KL2 zQ?3?)8>eC$CjkmQpBLQCu-T@>Kw*}R)4v3LYy5d$q=7wu-jKl-VrldTt1zHhDvT8S z>;VA4y-a@zJQl{LN_&T_uDmha1bq0d5b#~(N$uGeZc}LwoXAF7CJ!ct-LLqe2t)H$ zdmtS&1Be&d^5mj#paqDld=|WJRjmDtf;*7}$e;M~oo_AvV0`3fkin^AddGNk$KhO= z-E;Kwj;dske+i{By?3|$qOEVV;ipJ}9aacyB6$UcX`Jqsa{#ExaoI+3svp}|a7n8_#T(tQ{`^PAT zOrbo7pUVQ<#_`Clv9@*XrH$CVC4qmWw06s23pqR69migx!+CEkxG1yJrHZ2;Z@)z| z)mEE|^}!0x)s+>p9J=|1kr0{#3~87XZ+&s*Yl}_!}k21b7jXjg6pD8fMEfyMEl+zsa zolsgcrZbK9?v~Y&N$Y8~;v-F;+StmQwn{qX&6KqI59l+Nc+X?B1U59?H@)S7gisugWk8VM<5+!4|99Szelj% zp`p1piFkmkGS%<6YeTn!NBcd8PQKx{)d<5lTaJG=l}S;tPk?mb)&%5Ea{G=Mp^R6A zkw@(4!xkMnFEl0)lT;#kUlSYfi@E0we!aA4UsX18ot9g}53NT8xR}g$Vv@$gkn(nm zUFfRgtLXdfs!yAVRp>49(1_l4>O01IuEqNZRydr7Bsu*7Cq5)4zInSfXKoBb>!A2Z z+9CZNwX*IYN99fIG7B(_A>e?1GdLoxcJs7WVcWWm$X~tffcj45XnG&ZP*<#xZuS|E z0ug=hr0Re}lQd2mM985SbI)VIt4@4hSy%BQ3b_T$EBUsKUT7%Hq_QEj-P=1+TO#no za(qhlc|iTROs}x>EBIzn0F8V@P9~)EE^o1D&z@#KEh-|RIU?}_T>2(Lj3+c#Yq8bp z$Z2};6ZU_(j8GTme-xnIHRvBz5b|*Uhs|D||B%VI_8;!~=l{d+U-SMUbr34t-x$sp zY4}ghjL!IXAD-A>|M&q*lHA|zfTX~G+YqVF|F+%J8vn`(beW=mw;eOD|1BG3kHdb* zA5WUKHi#@ zIW3G09czg25z$#|(7+iRshL3NX%0CcMQG%p%aPTdMxX?AFgDiFzD`G3gFz-c_k-)F-ETM0#tf*!z4y=&@O;P%`sBC%+uyzun0T-ivAheL>tYlXK2K||h z#;3j&N10a$);tOHbB$Rmlg3jl+BLWt+#+xcFtmWFg)mcT*BBXP)#M^RI5k&;tm2mC zIPn*E^~Pk$5}UczzA+BX^6cR6gr^1T&I%kH6{QveBemfh@uZ$|bP@87smY%)f8=Be zau4;zi@YyB0Fgqzi$(tlp%Ab4SQT2=N5jewek5b#&o)5_PzA4Gc7Ed$xyh&9*pl2V5Tnp$MwqpmsF=1ZoeJm+{mYZ#CY7JZ1Yv>&=x#2Rv!nrCsXT)EP$D z`KzHk0i$Y*q-l85E&1w#;Jb%BN&ISdL&{u3FkVNSe~@oHRlgSQT0T%e0sP?uj($3J zuR$ujP$+6GvB|rSQoH)ras1hVE9+9|&|V~jJGZo<-%(Ncr5RxjUWVR&7L_;5T8Wx5 zea~Limo+B{X$q2p%kv9kgz9E$w;bQ7I^I;P29~54aO}aT?4O?@T#ocUurr2YuPRrj?6iv^XAV!m-z=bOtC5ihJ zxtLX?XKs#4?ot%?3KCAvfgRctsw$ZBP4Z+I<7d%Jo%?3`Ej9rm*A0N=3g-QHU&Gsv zW}r;6?%}2kWlvR^ZCVumR*VhYqOP=UF3g{MhRar!MgD}>{YExy2!8TfJc2jkFIWsWboCCMi4eWI4v}gMC z`Lq1%A_0_-{l+54Czj`79VJ6mRXzNkF(B+zpmhEGgd`Km|bbv1sPw>2wb-Jau!j~9l>B3zRi(%y#dAeY9WoQ+( zuoZLBif+b;&87^{xhA2qz~FEP)iov6u^DCeY1KpT@*RotWt=Y8cX8xDlGladUn(>j zzX_q)WUveWbR=EdTyw^>rD6>YwXZraV7SCaV5w7@;((Uyl7?NjAh*@)ig<-whTiFM zJ=G{x)48Tteu%7m3;eF5wovDxU`|NB{Ki&)l~=-Mt1G@Eg$Y<{|8~X`YEQ1T0P`pj z{0{hkV}!C~l3dU)aX2ur4vd6YbBez%`V)}R)Xvz|HA@@L3*!hkfC`2U7bKmmjH--v zv>F_Yi2{Wt2Db;RAZ;|DqnCN1STDxOcY0y>RkN~LJG^OqSvQ7Opwb9aPq;p8IA1$v z*`{f^qN(Je`?_QGF=vecA1glbWX$jV_5EdQhwHtC-}gBV9gH!-MZ>Ol8$v$@853yK z<)t6vZ_=bR9HJ44YI$B~IE+XOU#m4Fw|Yk^5TFkNdZPqS z({eoUqE)%C)~Yac*(yfep*B?FoD$yQEIe$fE&sWaTVRcaVpU4Ep?W|QteZN&(^$&46LDfY7ex; z^b_lIh0oTyQNU#y^-}3?jUq(dViDz7Qt-)F2-L)n!T%MWnk|h32WM)cX$!0{mP<9X zT&wCc%O7e)SF9aEf*}-hG^{n+&d;^y&{Ld+gtjeDsB*um58O1S+cs&IP30qKfkCKt zg5w#XV4KqA&HQRrZxFM>2{pz-Hb4PScd=-%<`|6|w$ANIAz!(X=XuswXgVBd`yjrE z8UlqCJh|L@MQ$(FkGaO2v<NRo_ z$M2YVi}z=ft#yoR+jgr8qPb9pS(wYF8S_}hT=$u!V?R=&`fZK7O`GvO7?xzc^rYr* z^Vg`_XC8ag1QYENVt2|$;;RK9M-Zp@B5T!1F4ngC8uIg|@1%{-(16iIC5mAtoB zUPslnb9?7o3nKK>$#}_{qjLlHKYcof$7OUFY$A(Hl(=ne zUy4m?92llmYb|uLtp*y+*Ai-tc}WaN+RfME>XFNjs@CFdhtc7_qb|p-@C0o>vXUHV zAlB@;!zB$IvB+{wiZk2%KvmoAoH|Q6}n~u za-T!T`xEsp4NNuYsv9$0sAWAgT$w#I{Gzo|%R}b}mByz9WAntMXzTUKmz*Bg7%sTV zqnI`xmh<$s8E@ml>`gN=Ii+qvFOuE!r&SwQ=q2<9duo@o?r8m7M(##*22jtFo>FJlPZhh66ErV zp}s-696-<-p1bA{{lt}4>d#uGF+f^Ke^bD)ou%d8CmzX>wWrMn!R|D%nfSeCkQWf; z*&HF{JVA^1&e3HUdkLSI8yTVPm{oXtMJ3sVm9h4Zo?3sTabt%9qwzOX8E8+BR1xG+ zjY+$0RQbjRU$Rc542G>}D6##f;_IYG`jJAsE#RCE+_&}%wBuzD5zQVx*HVoHUZ5W8d-!t`a*v zs$z9H)8zuya4jh~^*BrF72@FcP9aiJsK;34q7hxC9U3QF8!}z)A(|+f{5AIW^4qII z2!VTZ+H7?yjTi6&#$L)uIi_S+gxzBqW;|XiHx}lgu5TFyCRlQ|!8`C8NKPtc%NJYc zkQo>?s_M_(GmN$wu}N|mC#k(@sNAkpwyDEE+~}wG>4_<8af2j=Q2ekE#csn*z4bc1 zAS@xi)4&Doctab_8_humwc+!LJy?%Au>p@IU5&9iX6E&A{W%y5-hbQr2mrkxys3c0jFBqw=@(F%Yv84u$R-AQ^Hu}zyj z#I6G8BOt05i6Sq*4=-_7k1A{X5VUpQtKt9`F}EjA=rL}*DG+V?wbKs^_CJ+5aRN1_ z$xKN4OGSf~ZbUsb?x#K{&CWY&3IH!68fe(_t>`pX1M5ZkSnE`N~5hU(O`A7wGQlqL#WDL=$m0?yrWNZ>6|) zkec5AU7+;`itM=m0#ZNKui~QJofDt~R?15;v3TBUW_JIOK&zR_c9yn$-FW65hJ_v0 z-06_~ux+xV2Ru0KrzhE`UF$NX&LZKh17zdrw!EXa+0KEV5aZ^|kG1C}*s7@$RuRIL zqNq7C7P$!`Yu{zOm>Bz)s0TPwV{GdPhS2;9X3HD zP9gZcv=+Hw$gG8YILD%!A)JFa?K0e7JqF9_@Zsq@LrM@VcxO$_$wVeH-O%`_$$9wN z4n|TJs1xech8fGeUgOssQRB%>TjbR!aIX)}msZ8n^5Ku~6`o2%Q;VHWzN8sW^qfDJ%d8(@2{-|5oCs$QY`QyidzZ|wY)G^sHkXd{8HfVU`F=8-4$W76 z-zxnfa+C|YF^CggI#%6bjp^JXn-EaFjKd@%-sz*U0={1`ic`F@+q)#S;-NS+Wg(7CPGC(dcx%ktB zi^%**u~uAhpOU|?-V4ohk4Dx9lsU6UolW%&z#5P6!ehF<-0;G!*+uLO=em8)P0W-n zArCR9$|gRf0>7BmPd@cIn>OCtjz%)6$%}l9p?MB|F7IWIa&_*PY#`MHT}O*=&tFmzk3aSi&4-YnDA*s=C7!^(ep1G z$KF=`E81>f{ihz!x?Ezo009O@2c7UOjUqwm5FaSx@E^igq+y`8ApB9CUoS=!sipo* zn@c($2t^&}7b^QHbU7vu3Avlux?Lg2dR|6#5xCcLGlWf0#U{ut_)Ht72QticJmo64kkj{1ONB zPID%`|0jYYVm4d$N4z4PVkGVn;YV;7PFgcXt-m70|A@nIJ}x$ z4yMZv%8Jn`esB@+$-?OZq^eEq8_EreQD&HxyV-#no0d3#*e05-6a4|mgN?wX_cFac zu}Yay>QNJeeo&wSe|&AxE{o*4>w8lKf}ACCiT$c{rtz72R*^;)|CFCiWuHH&?sij! z?XKH)eb}WQ;PYkmpk3)AYbaNZFJ0rHuX=R8x}~(LQNpP4-FbYVC)cjU26js}R>sOi!;Fr-6dFV?|8Px#$5%2?Y@D^QEh>zY4D3vY@K zp-2{M8b|i=(@%=`;fJ4h#hQCe^3|^T1-=z9`zzp-iUez4d{oES?&21;Y9aB0oxa(z zgB7$&Yg)?-6F-lIusGqoW{-*hNvO|zgQDvsw*o+OHp;zSXuz=hr}3xp$4>sOAf#~+qv z>qxV(o~LqKa=tnU+ke&zPe|7%(WNr3Ibiip+YXEA`@HJ-UnWO%xB@`^TWPxW=QV`+ zXiU+-fPsl6?3t7Pvjru0xBoE)J+%d8ls}40g$#R|P`B{3CVH`88nG`$!V(h_PF^?P zWfm4t3jYk_*0g=8-+SO!## z`%wzw0U43DO`wdg0;Xq^+334fXpY+Mb*C~8!%plJI6O5*P_9d+V_O_s5$<_5=90qo z*a=qD!lR45^cjj43J$_ePwZnf7Y-GdS;oz;sM8H-%QX8mn#a0yZi{jA86Q2yGqGW# z!k%$AfV6ne<9tym0t3xBha408io@y#DQdHu5)>T7!ex68?*J)GJr8~j-;V0!H%%*5 z1eO7VBIDMV&fS;;#5RwM@PbKaWDQ(rxA9a6`v9I(s6%XHi8?X*g3BfaTIwFl9}c7R6BKt%tYgg8`Zwx~u%Q(QVUO>?tb{r>bw zY%dxTDpNvyG){B7Jt`&J-IS@Sp);hZ1H6tXF}=2Y4f#Pf`R#x z1o!HxSMZfVMtjDm^viOK?=O62Y0+P0AQp;?Mrz5#NuP_W&Nq#5Izj^&ly$z8|KNF# z1BOTHbB4gTzsB;3mz8uU+;1@=dAtK^H%y95Z$p?760n6VJcwXgj>Ul znPP3KrL*XKpm?OVkNap3O^MyWWCmfy6FX%jzF|Q)QUIy^t);?Kqg7}`3NmDiQ1V*& z0vw(bXAN?!dShqtNj&@)ZK4d4(Zr2jp%^q8vvV)W3TIJ8`;`9ROut-|owI#`A;p)> z_5X%C=?`Q^cFM4e>>o7TW2oKvFAM6vSp8SCO}#$)7h!;R68{Y9$#@#q6C4ce$47J# zOSwe`Crd%Nz=Z>fn3+i#+nXy}o12=enLE3iJD8gP9~)C0lZ6yP@y{BXV{r)6%O~Qe zP7jKr{<0qk{eUJR4eQmwwlKGxW__79cYT+iy9@KAVxmAv1SK-$Q0nuu{0y_JvrDK4 zVs$VO5kCQ|*v^dE+7xyH%fjvu-DMe+^i=;HexMiF46oie5o@4h&vtmWo`hhEh&h_D zdM&+xMi`T7BF5Km`>7zlRp~fi4wLnQqp@w*c~yfl(rbmAKfZrwReNV&($j5F%o~5A zH;!b-bBkH|EnOr)8QVb@uo5SuXb{O2N=8fAX4BcR z{^HR_*}KB<41qyV#HFl3D)kEwbl+GGnH4>lATTlNg3*j08fD^G(Yw5dzG$8PS8GvO za(E`DxccL%-F+0^1^(}og9loh+PXXauSceSsfaFuAt3h2HU$uz4?#*wnpj?`3{~d` zOFdYKBN`|EZr>t?yLz?!_VtPS84HCbj8gC`vUz8NULAS5=4COP=hdd~bXJ$;$;RW1 zA^7C(_wX-~6wJ};5HdWGrlPv&@bk3m%*FHj-GM+DS~MKB8)b9|z{>yQ=j2`%Lz||EFAc9|jXN0}dU;xv_z;*b|e~)F7%Wx=}897Ln z5E!{30gCQ)ObyA9EP}2)&g$j(-5wipcvLtBc`!QbgdPN+ZPf}o$8*SyF)mWUj1ST^ z;XSH1#uo5j;MxB@+IDckEx5uQQ-bgb@heb&q`tLdFI={W$RT5s$sRQHeijA_K(HD$ z5$VeZQPA6ZfiM9Tc*}?TJkYque{Q4L3cXooW9URWnqHsDh%29Q)hAjC@1VSp3 zb(APEWzlTz_EWTrypovNmpIa51Xbs)VgrW#KISFZaDukdJ&q|C$6bsp4L5)BI}ELg zAAi6&-rxu|9x{We;^njU#z0}l!8cOpu`o8Ho&(y;O4D<-y}m+V|K+@f@BAR4{?75l z{}%hpizR-?g8#>R^~TYVeb|8A$1d+*8=y@kGvTD`pH5YoR&{h2QYik=ji6bwr~Chs!kxJc{nq;QZR0RAGy5d-gr}sX zCjj^YmkW~8q1IkC?}LjqpSF>-80@jxHSzY*|)u zZPL-AwVS*rpJ`B3%*i5E)41C8tfNvJp;bc>NuV|=WG|rx-hS?8AzTm z7JLu(p2}PnM-wgl5qt($8}SyCMXkZ{Z9t%x)i~&KeUDOXj{uh`icurv+J0TM*&bP+ zNK(*UHrb4Hp*GX`HX>~Oqd?DTvCtzE*w~EyJ9)LP=}vSo!2MN?XqSjnOC^yYJE&Lc%h$1<>` z-0i^qSs`9;BA(!LPC`H(wNyc5ApKn{m`U*uPH*o<)KzS9#kf~_)B%e6Q*NqTfIiWI zt@NN{Q>W^m@I@MoFeUlDn%JcoWo=28=>^WwaU>1$Q}D&R^>Mg)sdpMJX9d}jpE$0N zxSQm@lx8Whck10@YcmyN=w{JzQIPx!VL@$+$l>v1?fNg{u&$S;wFNx`){81GSY=8k zlTH!KByU+l|F4F95X+(&Km89)+D!;}lLN+h*lNK?vIwI9NzR~Uvw8<3Q4qd~H-yT> zncb>sP0+jf7y2Jv$H#@vSv_44n|IdeAyD5AcoAQn`agF1&UE=-pVZU{fzg|Cz+m1( zW8G*E6oROr@3a$#=UHr&XX7JFc!$X~-7qKw7g!jbWd>M-+9$q`)ast7Ovvv03jxEw zHxaib-(>!pS1q!U=p6fw`DsMpfpp?(Uytae|HL?ob+w<*WYi8OQwqUbkNj#+v2{#r z?GA0dvo+2-gE9TxCx(>+jt>drjx3kQeWdUoWSS{Sdvy_jJoo4h{B zp@w&iVnmFf0;%Oo)hw!vcv@mS!Vg=AS-#ij{zbb%eY`TPcG=?9EthhaLp?YV z^|4`a-f&b3mAT`}mo=$jxcpqs$PJW|D$FdD3M%Q&7&suNNAZa z1>6xUuTc(*6Veg7Hv-p~#X_p+EAHmmZ3;{56&}F-&nMOsWeVUf+B>IC!$d#frosU` zRXwZNcO3XU&K_o0(8U-q+SaUO-SaLH$zTGs-j};I>c(uwRZkeXT4F>6lr&N{z+-Hxn$^-8Axl)H ze~11bo%`#{K8Ek)|2eUR0J(~W57oo_$Z2H$Ix)8YVqfZxYHr4+w*MhtRq6&xeK(82#VHT5gr+0Shsx(Bz^PNR6ywy-7DtPeuV#5adhCH4sNk*M^L&?Zm4*^iau@4Za=^&ANeWE$=8v~t2uY4zOoR-wW)$wp*mMVp=H37 z#Q75*XzUV%UCF@G1)TgGp)B8J7x4M&mw{fxxVeK@=V0x&d_SsfmcmG*JzDrE8GQaV ztXuY}2TE5kebC^J>%e2{tOu9$_7=KLBX&*Mk;Yj|hDHouv?Gl3s9y3lj^6;r=_8l4 zsgEJBg6@ZSN-z)LUOTq7)Ci6TP5lPUA3nLRpV@U-AOebQxubB%c ziRc!%4#N?VWwPmwRDZ2Ztbpxhf<)>Q+R7;j0{WB2a=viXY(CwlAOSOoRaJyx=^3UqD;(OIR>LqW|Wp=xy9Q-&5qLDHK-r3=xm!&``P?+h6CBvHh9G0I^?ka@kIsUrjM zicns{NZ?lHF=m7@w#eT|?|}1o{Bc+j^X-bVBu?esRCR+VJ+T8+v30QC4Q+>3Vq<;B zy>-ySAiciwjUMp-QT)I2BTbs%IDd1H7AFXBe29N0!0WioPV!*_z>hdC^4A0e|4%!! zNL9gcK^Vn9gV*^02M+>(2VY41jU2J*bEw=`NC^P|QsMZwj03xQhG+wi%e&i*)~}1C z&bu%-1t<-Q_awqkUyHKRveF(cUK@o10$z}INv?Eio%mwlIqybo)%uE~Io%u0RT`@l zmIevYJ#k$Exbd9FZgSDbjfS0U^l%-r{u46qp%E*W}#z za*-svH=p2_p8_Xol1Fh%M&l>4`d%|@6Gy*DBwv{01T&$C!D-ckG{(PDlG7*ZP&g`I zyNO10R-5BnYG)_tjM>;O>VEk=It^Pr1?%zS2VO>ytBi?1_^7Bw@3}ZHIOhzNWu#IM z3EijBNdz55;p8r>GoZ+^pr0_$R@)M@5C{t!(!D)b1 z8WXC2y`}=%aPS^3_)(su3c5Np!dN2Au6S<7?KpfTj58W9>y!JAtkkHum_ERI@vLExM(% zyBUnrhWrS69)l;#6*t>{k+o^K5bBGm6}NY=)gAzDN%w6ub8u44@Uo zpJMQv>Sf;P?{1>6<)d7Y23)on9|TOa1@&qHkdMLcNr zrAzFTj^4ehDpAP&h#b^P?OGDxgcl)bg!z5s{3_C^P{uO-V`^nU2&&J2s@t8Uh?+$_ zBc8YPdq;mm5d#6}`*Ku;<4*dx52OG7&rQWpGBm__I~Rp@7#qxbk?n?g^BEoYM+xjgWf6TBC* zECCNtKu&1^{2PMqlL%dZo};^x<-h{UoCFpQWxdLC33+-bRYqt*Xk_JlkBLUrVr`E& z8SuZd9%V_4DTUj=Q}|ghDObqgVkxx<;P4;1y!Ibm79Ac04~BIJ#itcF7RJI>?xSvn zk_c2j+F)j9=1q%cBV_QuXM2GBsP}vK(h|Rd360-vkM(N{<{GKGx4%4eJ!YQrO~mBv zbVK3{xj=_FGe&*MoY{q7ES?Jq$UeehG>;uJN5b8W5;>+vA{sZs(VEBUqjm+FA{-!S z@m%2zxI=Ow$io&=8tg2!K%x1+$w7>D>Lx+h16ERE=!!6L>DTFqSO@_}tK0E}t)10z zGF^Khh~I(m%T=w>zg_dg%h9-9hL3Kl zg`l7fS8MFivwpBLTklgk;I`VEz%M{wrH&p{hxu~bn}Ce53@F=iukME-kBRoRiY;69@MwLzN$&@1xTF51 z9mXLZp}DPT*KV~VN}P+`P8^W{b%gAKeVT^(>5AjQ+Q*F3Z+2aXBX3r#%9?jEVyyi# zv(qyoH309}Yo$T_eYG3VEc=mQN=Yl=@#^(>=eYs)cYD_i8pLVmU6Vo$#U1Y(F@gKA zFKWdW(MgWR4CT2OZKC^K^t^5o6cVQUkoWJw7z(Q2eM7iDOvKRd@hGq3B>bXu5t1UN zu2*z}*y-$h)W)==hy-Np72w>_=qf&*WI8JB*GJ8>jZuSG@fkmW(Z^H7Mv@7OQf4k2 z%z}NNze85WhGMjrlFo*6K0oFXo{XsrX>6%XE@3E1o`q$r2M+q;?O)sOo4VgVP_oYP zH*|gv+OW$lQfy+B64P_%ZtOfL2&qOZG>uopDshIlJgr!a0C!=RZ6FjfWf78LH|K*@ zQjuJmu1L?yOZBjn+|qraj69?wN6$HzmkP4xwl0dRSsyfa;lNNM3a2TV+Z2#69H6<{ zNGmnA1pXKAP?n7OybZDY5gOqC8I%IBDskh(mQX5%Bis z7QL69Q>-Ob-u5D$P6MT197Z(}L2R1Lwd2RYkg9mDC=?wM#O9Wb6+pcjk~J!ggon!6Z9_|cBv}x`0cO^hdy$O_lCdImbrkv?`c9sEP#7*kyK z45N?K(F`&rF=9QJRngq2m0grS%!_0KmRka%*EEXHX!#P@<{$%8S4$i{weHmrtrgF= z8i;q)=PvJa%hGM~8$jMFT%swpcq=8GV9cyocy2szS*nOCK9K4s^>cb?9bVl`!3#8` zVBn5JuQ#Hgs>lsg9{hTAAw_Zf3F75ap6RvY4-{~ajAdfsh!y8H6rpwCb1!M|#fUIs zS~z8$5bv|tSc!V5YDY=#Mi>KU`v%LRR=O|3Iv+MY%_g8(ym6l%g zkN3X*GVw`FaH78#DHqt_l7AQ2alqOBHnCf*@xi_S9XTWfkNexIZt)}szlZ6*+5T5a8@!jTkt-vD;~;7r_B+sX5GK zq&vQ)Dio+QOkXK_gj`(Nd0KpH{#9o0-}tNOyG@njIV6KPnq7sxzircV0We(XbmTfM z&0oYyn(nvLRoBV3>-1x$?{Q{_qUUdXiBi3jzv`B!XGX8JYvSOwJ1bS%70dG-6GcYx4lq;PTX0sSU?NnLpAtn5A*3JsJ`;TN?&?CrdA7ED=Q)TnYdft({jGo+#k_`ouM+RL{q~=VtjTx?@1Y_^pC{niUImHHZ8tIvM z+$l@?3cVcCrQy=Zx^Gy!@iL&?jfDGDF6ms>yufPa@FC4*i1JK%zA|y)IdyLnxG;oB zu%c*1i}<&5v3RToNu$s=FR{Z&PXu{^b}Mt#uywmf{rX)$I+;}tJQ zH7?#XXHW&xbNueJq(Y__B08JL^wk+?c_h1SIy6RNHk2DSj=<~-jVfYN0vmpW{YwmQW(%}K<_cEUQ=HZ32c zZep>jWEhdJ#LpVFnj}vstp!#Zb4jO4^ zx+B&8STy-b81if}`EsL`7Uj$Wek4mK{9LBwT2;1B*oL`aJ3?#MM;(Y%kZB-OUMDM` z2AZ$Fl4nMzT0UOtPIu`%+@N-c2obIS&QU-oFC8^kniqy=Jr9AbpvOJxN){J7{o)eW$Nt-{mS== zk#taJ15g^FeKNg{J?Ffw5)kZ$4^hZB2MlLyG)C`l1z#}%^Isk65ozZNrpZ<|NOc0U4Fxk;F8z{hUrGX2WiO^ z*V82;sGRW5E_g83BL=lE6TfYUZqN^d9H-v_JpY6f&uu60hPFI$*v`h(-}4nYD?!3D zY2(19B}=c@!?I+>+>Ywt*;W1AH5Z7028MH^3HmJkxN$0+`q{@B8>khKjGbeGbCTM2 z52c?wxrNv#?^7EzIopwG)XY{AqcROM1t)h7M7gCg5KO8ru^GE#x@vKnlmk8W`^&A~ zVv)-IFdWoO!L&CrIH?!h>^<|);ltM!U_1vwYhF(%qaRl1SzUCZ|1cG2*#-XImfGy? zl8=Ak?#VfQ0_&*>@j6z?_JOkgqn>lZ=kQE zPf+qzL~85x-~c;!(c$8(<-g)*R}u73-IG3-}V$EZ9Gfnk+azKVr6t zEsS{GgeCRX3Lr+_#S!eAe*@?Lsszm(3IoahLPI&?y@is19)NH_lB~!obI&|5PeX}( ze}kH=$mX3GlJje?4s3dtjddD&78pA7eA9}YbH8^l=+_s*^n61>+)aN#2c9{gwH8IS z+El~B!*p;y+0%EJA>U1LAcMP;%uHc7`0@}MJnTV+3s*cTC}6GI*KNjaWo=`3IzL1g zC{r*}8)#ze)HRhp%4#D{s;k-`e@j2qzY986FWkZ!Yu{wg*WH};ZJ|Iz0J7E?oGSo4 zsUC8_lF*btULZIys|u(v9MV$`gjX6j80$#N_diqy@;9gpOk1fnv?mub-uSoK z^HNMQ)GoER%4RnYq0>bCqG9tq*KF-cs3Kp)bWw`=k&HKm2MAW_SeD|%G?`FP8IX2Z zK0qr(^p4nVs3 zUGgm%*f5))&KZSjV1R@QrS{8{WNpwmk7sI#uG{U6+OM%VitU%0YL^>93+7EkD^(n5 z;pf9nI0hoTtf0fSpN;$k9P$i~GAEqDrX_)!=);x=+wUD@|TfHXeO?@0u%4K`>$ z>cevOM=gaV9xw+Z!gR2{r5cMP;XUNS65e8 z_w@AaW&JSga$-RJ+ZaFb*xy;F zFU4=__f|d8|Dlid#2LSsZ|?Wjf2Z&Dyhr`x!?yf(vG$vePF<%JIem9Mm|YTQe(=a< zr|(lUEDp9SZs1aT;^upy@2g+`&CU8jpyQC^b*;mOXU&T6{aj^Phb>uk@5KK+c2pae z9RD-#=qvx^vyTGCb~|$XeCVCaVYyMywkE}&=$^LgVDp9j_KEEt+WRCpeRqpd^d4=e zYkSzE;q&0EBO}dUF6oyvw$|V=X+Li-tQNd=bf^7SN)w{8GfE~;&bYUH{G?repDW$H zG4k`SU!&)>>|!49Ai}!akqjrR>s~!e{{A-m*Dr<9KK@~ef%EIm%?~Vj+caSA@UGAM zw3yIX)1~^A+J8JTJJ4nE&e3Mq`VL)mB4T?`y`-5-r{onay^{7~$jS}pF6~S2TbQ&- zeRj2T{a5FlTL!Pq-m)TF^68&(_(JUcn8B}Kb$q_xx?SZ(kArVNUpfDO&%dg|b|iQH zBmKD3yulHpD|Tvm?(XFQi+lX&b7)WYH&s3H^qoO}cs`l+&35&SmRY&Crgt9nYvnyd zzBdaDb?$kxeb?){DK~c}7kF>jU)-UE)wO!Py5_FUe$qj=ckb!=;@6>V?lx*Ot4aGd zbDCu=a^9Wf*08~jEk73jb*<6pr*Up?Y@~PpOfR&k=A*fBb?+|Mw713PXZG$1%GvVq z;mpFEHGecjy+H!d8lC#8P7F!OMy=L5SA`ZPH2ue(c&o?RPN^+)Sws?wFK)l#yy!Pbs*rA2@QwJ@s_h!`CQ}>f??>;F`nU*nZ%;z1pYZ_^+>R*4G z^}b5`2lbT&i(^Mh$GsK*YSwtxRj>5T>eZ|2!1)e~M>vd-8hL%WWNEq1UlSescwka? z@CWbJtAdha7Yt0Y8Wmi#zy0L<`rA%BcG-HhukT}Z z-S?qWH*R0_bdc1lv3Md+U8~yZ`m^F<{lvV#+T}-;yr__TOTBlS{pCfjgS@BhJrmW= z>}p;?N5z8`MVkC8v+wzaE}59H&${1 zPU&=_WdHcvMU5>VX&pinaOC1-EychVWXV;8+$ENJ*G<0cxx0Jz8`|f!6+s?wP zwN4Gv{rb!O?BJ%i9B*x^+s3Iv%9@RDDwKY@U-kO58@p%b9=Vfb|FP|a@YpLQ+AAB= zPyML!i)G!9tA1Uo{hsvDKX;5nn~!TBMd#Jpv}x1o=zZIw8!w8!wY8u?^>*d%w=>k; zhC648W|wv+t##g$lri$xL0jYMc37LUJ85*|9hX-v@<}?|HTO&79k*9?_DrhLHFs+7 z#GB2#>hH+r~WXr+c?{WWNXar1FrLxcO7TWnJp}X3o{cuA%cOdQL`KzkSC)0Vv1n)7mSosOfmt1fEK9v6d`9)B_Svi;~Ut`p)Cw1sJvQa09z zA2eda{+gfu+#aG!nxWaWsNQ4CM}PG8t?r%|Wz%8#sHpaPJ>yyj53SkkOZ%|Tm36_- znkJuF@x?3R@saAIQ=2ACZ1B7=b4=K>y7O90ofmw_bH3%^opZJax1PRib(i!LA2fZ= zTE@LOvTvwQ%7xJ1f_L(VfZu zb54w4_xI<-F6`d=yx5c7x1SfgvAg31u{*nuz94pH_ks&zBD<>#L|2N)7kwBpAYY7U z_nrA-l7Y$2YfSH<@1-t(&1j@@@(S6D@pQ=KIZYC9;9S6y_WO+vv^}kg!{ZrbPTD0Yk=%koHk$1%Y ztjcwFpwnxTUQ#OLrUeuNJ2n|ubNYNkWWOjyxeU8D6Ikte6J|M)-CdFWFc!Jp1s*b6 zj~C9ir-=r97Q?U1VL08sE9#i+7lxgiKQ9XJqFdY(t@ZYQxxTQC5A2@@_ePl5FD;<^ z_rwOY`JU+D!Fr*-&D^D0`1KO5XcN(8bnl*+q}R8zAYo&B==%tLjZK8?|J3W7cj!+m zT6mwEU-L0cI=L8TR-Tu<#FAd$7uh#I^z}Y)n04!m|SqX-!RPjz3YR$$>(i@L2Bj1S&e7E@Rlwvpub%%};p! zdbgQfpw`dCD)WlZtNcwPJuzmKe`u4zH~{UZsZgPwNnOp2rJU%@Q_;FI8ybl*1+fzo z8^W+>C=hH?!19W*8v6ICC^ElXe=52vh!UTPfi?bH^>U9ciQUl5im2W+${w%+Jj!G> z$n4Wrcons>kX08jFZq!beSgNAYyBL)_+(^gsLyjl-ngaur>K`=jsMqOCSMzvRNtGIP|LqNpnESx7el|9oOU-U+2EtT zE=3~UdMUaY#M{3cw6ro_ar8k~N1BK?{ldiKG3sHgKE959r{QYF{~MRBU!fsZKlD7D zDz>8D?<77DKg&-YnxQV#4LNU+&i|@P*Kb**>1%6eJ z8I?$E9#ZBh6_hC`g7m?m*JE-{&_s`9#$_Gk-s9&6>F_(LqQ3aT(Axj(MMm5Tx0oip zU<+P+!9s-tJ^x`ad&vIDNB2X12jrWWRM*N%FW-~~y%nvi@Ns2wg3CmDu#KT1sU@Nf z#e5L8h9bs;I_M+Q$+AdOUPME$EfqGjwAf%)`Jspk6`Gk;^g$~x#STl<{O_18e*yg8 z!jm1#3s=$mOa7)T%A}%`l?<|vOGG!lY!%B(>C9IL;j0)ESsXXw-DvBqaApou>z5k3 zucA(=aAn=^MQp3>znL}vt>~(3UM^5oU(eXY7HRg#InPl~yh%M1J<4^Fr#m`wmrkKI zPQP252BwkT?Tnm?~kId zP#8^FAH_hSLJS@JCL^WFTO{^(A zZ3)|J)9Gl1J;ixQTB`nCl!WlsdeptSLdQ|ZIE5Cg1ODINnIqcj`NiMi6>VSr-?^6+ z*3|6>7W)nQ>jAg!3Ku%}Q`FMpo+gFA4Ak>)^+fM={)uKh8mtF)|3u-w!}NdGC>84| zycVpG>d*rGDU2Phhf7Q0e%G=3zkd!>*s|W&F8ED?#pwV?39U1@UmGc;-ol1SM#7!^ zwURUaR6umfOb&ORqVU!$pwR;0<+B)^B5a&Z3Z*ne=$Ne+%Q2JG)L=R?#YUy%CrqL; zw3(p%lPgL!lOlzst2lAPOll?!S;L9u=2Em^yN>Ktk}vHxmpTZ4t!KnQ;qyi=abXok zR81#1{NX0)I>%I=LQ$3lt_e2#G<+fq`I&Qhu?6r3<3iNfsDoba>)Cn%2* z!8FrKiV-SYWJE10JdLgptzrI}t2_vQKd%ren;~x384^w{G?E*QD=_J)>o*uLP1t{% zmnyV@($P=3}s;59(?4-IBsgbN{i!B=Dqol)57*L+y6;4#e4%Ia`Ga_*68xdaun@eVN z!VdoXYRP#pPP3p;aHZD@xVEtttl_qtr5|AlD#4b{Ie?eTcvJ06d6x8DE7cd4Y5xlk zwwFSLv-U>Vl5(wtid@qtduWPxH1cdI)Hkd`8!Irg%O@cqz3JAM6V65VniJ2rxQZEp%ZE!QXpR%A8B&cA zLxovBT(+At!gPf%BYY{Kl4M1_wxXckc}31B{inZ?*H};ob7FBNluD`3i4+&fhO{o| zIjc}3(p1D`j^zBd(|XoU{GsF}zS^H?BOu0XVH8RA38i{|vQh2TK-OOc1BxT1Vs zI~nh+s}v=4>nKCQ+@w%pMQ0f@zKvi_>)oK%v%3ub-d@m=yF1`>Jvp41EU0LVJ6blV zw-K?R8}3paA+4_wab_9SPuSR>A^J?+NH{dWNZ3+N55a{ro{%{-&id3OO?_om&QU+3qH*!YDDw3^mJe3Aik-~(M zRBl6pT4zbes-O)uhjYZzTdF1WH4us3Q23XDh#YQbOS#^VeOQKkurs5h)g)K4tqSG3 z5nP4mCp#5|SA}3Z12U;9GQ|9H!kjKwMKuKmL=&L1A)jg}pdHCo+z!y$(Kv>*H6Y7t z>&#hQe!?sRa;UD(f^2<&oE%AEK1fP$$g4Ug$^5~B9R+@aJNpa~MFm!{y+#+9e!||~)-Wy+x_z&p}sZX~@mI;oj4#A7#Ieex%Wb&tw zeUK!Qvmc0czjC6NAJS36bWXTT5*#UO5OUfLKa_4io5LPcF@AJ4&>U3`M|#viZlgs8 z;t#M7GWL#TM#O?_{85eLN{-xFgdDfH12m8GhvxCCIlS2)lhYl{Zp<#Ln&|#38yO){ z_nH_*N49ceXf60)KSOHnkRhcT&{*GAP+Gqhl%C&hGnj-0s! zZ;WXJqdo+}sEH34oFoi>%I@A2aTlvIJv;7+Nd&BW&CA~kLT;@0f$VEb?S$>087R@j zV!@dPR@LcEF{8D$p?T$Z&MT~q>C&tM1=WQQ&wWAqrfRepZZ- zC{Uq9yS725fw@v1gnw$dK*M0P@UlH4ylH7L0%UW;r zwiEP?ayQX;u^JbsSP#zr*N+n^^`v@2_aIK3sfWzwSCi2MhB1Q8d@|!6Pr)u#F7Sx_sq!@)ll-F#Br!UAq_=c!%=_uR1Vur zRBFicU%)3am0FwfC9^k0Hbm1lhog7?p3Q}=8^XT(RMHUb>CzCLT$)3z8%geTZZ?$b zhw{~iP~KuOhqaAhK#!G-ND}PVaPaOj)EH79H9lwr*&6FP>>7cdue_NNSOu+yOhyEJ zKXM00A~q@==mtaV_Ztxl@{PnWy>*l$8If4MwmD}cEa-V8tpAcPL-I~3)!foPQK)^= z4H<7`l+;MkouV2`RjFtc)*IT!=!1ntT%*%!9xhZ5Tn{oKnH>C@2!yX1}EIC}<6qD*v8zW&xt)kKV=UR@eiblk4cI3o3 zwV9TWTrmbJf<+D|#=wK;-He1eEpsxnqk+jR;+SBv7w2i3VPTu+&4@0-YF~DDqqEHr ze9``#aEnEM-V5NwMjw2#HLJMHD+^+wYG@tW8Y^`d%)^+Bj`D-dT-- zoR{4k3)9L7NyfZU(lIgn_M0r8HE05>2_;0=kph zb6#qk`f=h} zKeT&5O{`is#zU>!FeB_jn+L-ZbxXj?u^e78+RU6{TjH7J$^;`~=;^^}CbgZ;GzwVK zk~A}C-tv%EQ1{1l8E;H0DO?a|b0oi&6sj0QJrfY%0STBew=FR;tY~TiLU8LUV_|bD zOh8*)b7e?GB9d#uCK=+f+RTlmJHupgG!Yhj-69hxO+<#PgJH}%Ik7b&^6+j>%-UjB zi4L^JnBIdi&DcHKV2o+nUM%ap$nwi`3n5=4PE|1A6TA9?! zj_BTAIvMh_BVr@MLxyzkgcOopRfhC-GuL~~o+K}GJK2`XnCddA7GCBWs?`}S@U6+= z;x3XorFDk7JApD}gRi+G1so_F!iFAAweJ5DA;jmpd^wa3}oEX4}&7B$HN{70^!EL)42{qMd59{@l--6C2 z_Pp!Gq;zzkGyFZHJ4~6_k0BD}cSqiCHi#2ddLTyQhEqW=*fXgI>bfwB6HA7eTeJ0} zmiiAj(R@6O3;6d$(TEIA-0g||w(Opm-abt+A|XQN?~HJ#)Zff4s8KJl|CeP%D$yOb z^4QS}ZI7GF;3VNKUVt-G^5>eXs6}rSP%bhe8XCF-1qLiMvFF4JF7T$e)Bw9w_xfNp z72gLfsk(;l_rX-SwhtOSZapK~37A=+FL0BeCZ=QrsU8nrAK=*(ypN0E2?Ba%9T@ z^eJ)*`bMN51?a6?&SlBZcOYEj|CsZV2SVwY=bQ+5Y;H;W1|q2Xz2b=7Andy(;*|~4 z12%RtUn4dWd&6T(2SLw@Z$_RurMxqj`0#J`-Nc)#%&24tI$-EK>04Qw(irc9E8|t8eM68?2YE80r{GY9 z-Ti3dP|Wm#KPPTiQQ1=QP{i+sS{#W*oTTzQ;|+7O(oC3?=!j7ziBFWKK(Zxg(@-q>zmzWlFEZ>HbH~V{%X>o>RDXi z&M2v+(0vXke5a`@<&1{#kkQbQ_yZH{izBLxxb+4DID)Q&2 z!GD?9eR`cyDq85fkrTC6p)c@Q<0stP%8_;JP=0qRbX#sTDc^4g7YNvh5Y<1CT8~5J z-S==fVjN;7yYnhLnlv5-3T_x-2f719QAmd;AOUW?qH?B26Cm=( zeJ=9*1Y{tuC!8q0qpCzjg=pZQ`z8%M_1q|+qNVp$Sg2OTWYv2j?CttS#`}9BQqzdf z4Cy9>e5a@k?DX$e(BVlic~6GaROo2V3HM3pVRI`zvEZ_WBh6y?_#*WpymCZQ(+Jzd^kY`}+pOiZXtKvqv@MNTYDr{G7?$#EvhM37CrMqiQ@S-ZX)V zZp+}4JyY?nK%lwPAo6-DrjQ#+OhlxlX~?_^mtx_aF$?5KaHg%i`PrP!Hp?yNa7-oR-V4(t&P zDR-8MdB5SP8Z+zFOt{WwAtQ8jbq<=BFbmBKTgs7~Szym!!Q0wxp#_c=)rK-53l)X` z&Eb$N44-d!AI02td^vi0Nuj9DS&3HulO^FW%6iUPzY?yBh%ZaRmb0Ow?iS7~U4xqA zXQSo||8V5b^@!bnv&*D+GU=3EocD4zV)Vs6PDIYZN+jS2C+;1x(9p^`Sk*Y6HX@by zW5MEMCLZ{b#|7fE;qsJxnwu@P7ecPEyN=A}qD{%yC}OjqTEb@~k`Vcn!L`W!F6>$M2LwOA;K=7cpl8=>Mhq1;yl3}@bY~uV zIQAPSTFwWtO`wwHh{Z`y(7D-Pp#?o`PkHm<(DPP$Ud{qUX0E2}ZxwZ3Ahi<4*zWItgQ))q{6iZ_g~T?k}bAV<=DE$wN~C73m8AvAUi=5Tf$OAFev z5Yv`6M26f8utaG8iSj2K7-1)x6^HVF{)zIFnj2voy74C-bv?0$U{#M_ga^~0MTi8q zPDUhLnA(*S2}zdDvhez{2+G2H8hO@a*U3_%&5Kb{uf^aU>ce@zceTVuz+zYwJAfna z7sKiagE(<#sboj}mcTQev1(v;=#jHau$pxkEkkN71+oR}2&2r*rRbD^2}Y!)aCtH( zmX3oLk+S@R^r;MyD0(6g{gd%Iyv`C{&*bp#DQJ`)t_~@o##|0}UyeYTGM^DTYBkGJ zOAAM#UAt#n$`h6|F@YrE53CMY9bM;JI&cs5=!l{G>k35P1gsBMV7@!J0)B1sKSp#B zDq(!Dgyw;NN%6wE&78RS7wY^AV|gXkjzibOm$llWPQNWCbxz;S1h5wR9|rWz{hV04 z-O`R41VP$&kBRiu!%UzC#jV7AmvMp-slt)79IW*>+_&rkC(=%$LcJsQ{|!g9z^G;g z0Xx##!4lpWuLAt(CWl9_!eC!j$caf;E%n=hTKd9dJRUIEi;8ccXp7b8gS$^SvZWBQ zxq%@^i;OZVDqRgb_P&uJ-PfRTh3`1BxyaI%&xF_4Kz*Z69JYIdVX5B=`})D8%^mUn zn$@4O7SrGn9LU*(nEH1uCaBjcPVD*#JM^zkLf1iK8*2`ytb-kIG@LlJ4kKfZJtwre z2+v3-BVj|sbD{j3i$OLQ`SdSWV?lEo=4hp+-A9m$6MG>NPFJ#$PhHhKx#*ipRu0td zd|ATIS`TApSK+)4Ix9Q&jI5>m4Axa=u#Q|d;HfaHCMP;pwQ}T{fi^(qN)U%vRJXzr z9OtrE8zqcqk7pBB9z1iZxe*&qP4JXrK+I^)MvSd>u^frq1e4PuVVgc4tTv&1W-B8v zLa5V*5nY53?C)rJEtPd>|(V^|aE`x;bdy z%|2H0K@~ET=5E1K&1N_kygC4a`jueStuVx6G(~O2GxLKqcK4z^TVZ)Fo+Y+oAReB= z?yi)TZe>F$+Yo4Z(-OJjG! z*b4_aylE#oVee5+{JPJo5>w(Q1fAkYk6mzQ(OC-Ghv)6YlUBBrav6r+*##9-E*N3F z^4g73H7|1H>uD>)RK9381hX%5I5`i22th5qIB#NOES3qZf`C0(NW8nri9;9BBD@GN zxY+TkNs$qSTq@!!Y$|^)wcLyPuHI)nFIsa0{aU`e-iz_nMU3aey}S>I;sXWl!(oe` zd$DGC`IT`y3Ja7}vLC~v$2TjimUm;>aA6;k_ZM>pyOG6yDNym8iuWV&w%?EVPQV&s zzf_ra>_>c$!}?)A)~$z}IhgVHz;DlJox)R%|^Al!N;m9us@IYBw zjS&)^cDFW6G;a^U^dU7k?0XQyH6VZ!U#eN__ffSJ=4UM*Hw$Z1!C@%5eGn$agmOX~ zWNny{5)a{p>-KOXY(aH8ATQ<~LPgGz4ECVMhot(7kCcBH^Hsych?AYoID-x&AFqyM zLKwl5ll7Bx^kk&QHY)H&WW8z(c9^L7=caUe%59r z9z*M243Z&f#}MN&DMm!gA4i`bgPCteP|xGocJ@7vJY9e-{^M|ZW;(m;D1M~1n!U-y zD(M#!zg(Qil`Z+jx*}T=7*=QTC!n#zWX|g`9>z>P0kt{58j*@@gGfu?nPBNOBWyRWk(I=4|r%*x01_pN(I{m}hwbmm{uuX{_lhf$bCc7ByN_LyAov4-r#!u=DB=C!; z5x`#ixFto~tgBIE&$9H@@C?SmInthm<7l_F3wv#aBY{ALS;xr!ELzikzqKQ6Ndf$U z!8K1axV?~@M~BZM@W&ssww7%Qu0j#vem>)M6!u#CFJ-&;_v>(7uHWOiE$R303R zO{1=gO4RB$x}rgff!cIiYO1_FQcd@Vs=a8_V6_Fg-I4s1fxqY>U;1i|p{svsKKTwp zZ_`+V=%G7O1Ld@I1LaXDg(=k&3{>GLwH@28@>8~%WPolKLOgehff}C<*CgD9K%?Ib zkamI^ucz1+*WtUU=loPX?n%oh!mp=p13$GzEf4f+dnoXp)JC~~pPCBxsy!*|AGKj` z>cl;0n0e5EcijceRzIM@=RR=Hqk6n9rQJvUf1S`%9(4RZoHX^GzE&5~K9CwJcRVPk z)HLdW6r}v~kpVjN0A8H+q+Gy;dKALaA?mWB+`hyln74m1$WADMa~1}m|8pL~oQV}Q z%=a$j@d&G~#Lv)C^uA0-(Py=mzCM(!mCbQ5woI&%axGr9Fls@nMnw}JNp+QL@WgIF z)O7O^T2`tvA}TsxQB#S+9|LxBm%-B>OTo%S4-F|QX{uBF4fyEOV;I%LTSNA)8h?s> zf+9Ps=_zj(NY1q82?Xv3=*zg%79Wk8UNb4zx_Zck3IjB@bn&rRk%vvkr;v9FDQAjo z2iOo(XM;5I5nny5TueiyL1^92r_f!}*nnTa#{!h_OscJ%5G{w+K9fR~PO)<6MTEwM zeO%zDeArx$?~c-lG=t%nx;^J=Jn82vh<9I94q?0K z4|Ga=e{^u#Yt&J=q@3wO2j;`kdgd+0bXZ=_v?7-`QX}P(bp|LElyGbdZFz$&D(4+J z#cZ*&3pXzsUyLQ*BK%}L{vNzlqotW=P~DeeWTJWdfO=Bh5{$7r#|^47N{|v(o+zhm z=x&KrPdWUo0Sb7Fj%b~SjwsMnrTK3${$lbC)T_5xea^f{f$yZ=%4L@g=)QMSedX(` z21RyKVo&#=p&xns+Dje>my95^Nta5!l??B`3+}vvp;KGS;yjV z*H4W+ZFyU8frDQV$>pPD_a{`7Zzh#jRKVx(a_BRj7OL9G zkV;>G9IhxsQof)RUR#uv>MZn?jD&_Fzhc*G40Z{a(g;Ued-nKi7@bdjZRMs%<4OJ- zX0RV$QAgikPPF<4VoyCrbP#5Tae;u&qc#exhSX;TRv&1H_8<{=~c~j9Cz*6X|S@!dBEpp{pyT&NCw6LJu71GnT?h<`7}bLK!j`Z%Tw|i;Rc`ofmY0 z!WtYJQtI5uO{uFbyump?rLLv$_eQ;;-OX@1`4D5g-CPcQeu^aSX9hbRc9o$G1poc| zzjv7F8VR-jWxm3}a&y?&<1i<>n!}>m$2qad9L8)tVI)+PalqDzc^c=(RZ#uyB)`kwLbV0&zc}Ao%)wFL-YMNl7t0T-QFe27;*#d3->kdcUEp_#U z?0cLTW~r+u9C*ZugO)Jz#WQMcrSqh{_t0?zhai~sxpmqDlSq7wZ%wUq-GtLGX)C)g z#d6+Smn^(0rc4{1FDsmMj6ixiwJ%7HYEE=EYUEC=ps;E5Ja<$$QM zb7dpTPuS;DhT^TDEfiIi%79ivs;=yB6%Dh~H52x@GQgGcopok(-o*|_P#oiM1;Vt5oS&XDc(xXfPpc(E^qLZ@+1XR67B&qG`Y$iCx}6Or+k-c(fs7YX z$F4H_sL0Sax9nj-X}C<_La-e+cO6hJKSBntsBh=MjP?`OMw!Ak^w2>Uq!>X#jyi9e z;DFGNtO$SS#LDEvrgmytRuSzQ)8fDIPX;%SH-#OjhBG{5(ZWui2>Z5?No{e|g$oyx zWQeVkE>tM)DMJo*va=#ze8a|?z%gQ!OiGEB`Eteh7*x4x-emE8YhMghpc|e ze(VCJOD8aRvd}ey-J|J@2xn$bWkfaVH_=X_a0z!l1)OBudCSY9v(DWgk8%NpOb=PA818IW2UDdTcM0 z+gj|7L}PK*fOw#}PUmFoB_0^*J^%AyfEmFDI6|ryDLK`UbEBEX*0ylKb2w8 z%ZD;vQDvyjc`QRBssKrODnr8V!dK5VD8ID|%GY`><9)qX#0=xc-9-`K20s_1h;I z()A6D(!V2nUkyg}{37Fplwc6)c}YItHTcGPh)Z+I^1&b+`@@Jhu~r*)fWLk;8N3~l z+QRxlqSlTb)zFf&vsRv_M!CzR^89pBLVX-; zG?uGb1Cx#I5E*j2H|mBaLz=SeXQHlO3KzwfR5nyxL)S#8J=_%0&`Gw5sGn}r{b6VF z2%~_S_W8r9F(ZwLIi(NPs>x%p7XR1kmoPuJCW>srn-pduYS9aL@m2IT#;b+5D@I;X zO*ANKJV)^PmJ_*;(yHjG9h@}07NigSCgUxh04JTU1-Ir;Gr}!}!s(pA$6i|6IZ5lN z|45v-U~K@Dq~rSwRwV>l3VsVXq5lvpHV__|m?J~tW@~+9liGc(9);3{GJ(8oZ6%pN z$UGDO<}8+pjtkPY5Z*44AqVGc-EwN90Y8_TqH1ba8*w%6FC!c${I!x19+bLR>p*UG zP^#$~BVt4D%eDBm2L;-^unvq2$d&O5>mVeXY?L8xs}L6KC`R+vq8rzs zzVUUT_)IVqJN#qh;YEC1Sh?;bL;4D-_CBzhhu}j##@GD82MGjyAgs{u4_pxT{6J+9PSVqZPa@HSe`o3S6yCMIdP@-RsA07K zj!CE!%t?-B=%B;2MF{ZsW7s4Tcepe>NbvV=jnii5pOC?Vl_bJ6xb_1fz`$6blO`;c zfOZ}j;+X!SY-?0YY$e66exH@6sFXEj>eI0kri=4RzG75uu5c%rCLziB&wUza_3(e&IbsFVxb(xbaAJ<}(q$QB-)~_4 zJg6&ef~67j$P~h^E4xGfRjySaD2A3U zQ`YB`s*dm&&am2C&ri-1&gYA6+ne-^N@)3|m85)@OA7Ad4m$LU3gJbkFlC*P1osuA znYr$h+M1fGHls<{rj?UX8kK|<#D9L=mf~m4S3cEiN{nt8vs6_Dz*4ci==Mhc5{R!WF8vQ!%LtMJ0RuzI-Q&|$qn7`%jIz8~A{|w8Bv%OKY zsu&~Es%@55Hxghj1Ii+V+KCYRN`6)&9&Zaq=zCMd6~#bhH#*_3aGc>@Q>EIjvagpu zjQ1XJR4mpzp>$w(*IiOtV;^&zWdX4ajKbg@kow}wLOQx_%Y}z}b7N{Rdj>@tFY!&f z*-OIp@HdR4H|O6p9tFS6%KdX7DUYqSshD9;Y;fqrVM%rm^`CRd8bM@i#I`I~V>0Z( z+=7zn$Nkg8_`WxVoidiFI9&# z-vb>zpqks?_0vJ*+yTp++b}wQy?2C^@~9ZAVMeg6*bWXx6q7%*XVm!<{dn3prWl!y z;o&_RE~>Gg!hHEI(8#B**-gL;x@vy?ZwnVZL$sYv?T^Tf=Jxrz0)v3p2opJgpjY(K zfnj46oGGknlIR`OWQeL#cM5Y^>&W)?IN=w@^E8>K-)L1b&TVYHas&Uc%1w$Shrg=0 z+)2l~(NoWrn`V#0HYzy(Ok~&p-K9;moB2g%p;y}tQU=~}M>~!pA-ie54U4roZLbw|t;(l`P1bp=J*RmA;RZBAPr>=upr2s>UDH5|T5zMXtu^?^Tt%~9Awqxz16zjy%~g)1 zJWr$~M0+Hlj_Qg8E`Jo`l{l_(jn%S<9_ zM0lJoUDZ)mSooK3qNC2Qz(8KQ`;5r5lDcq8sDTII_cxMf)khz=RYfBJ3R_jtWKbBM zfX1T=e5GfRk$fM{r;)s~4*XQDlurdTsNX$wsWnlZ?j-4Nb(q(nnMDahw(Uiq$+E!+|O#K!gMHiMkzOV4cQFnL(7!NHyH)~e)Y z@4G?w`M^dM(x{bX!nzt~W2d0c9L{gRt@!8HVi@Vnkd}5NxM->g;PBfa{3=$!Y^cUPgV%<#8qE61;4a4X z@a(04z~m+6yqhfz?k{Q{4mGyW?ATgIX-TbL3-E~SkNmpRb;TwGD?C(~e1n{y$g2q# zy&7l#lmn4AjvtUW5L_#-B<5W03J>R&=m~i>angY}2R#1Y%8fL_LLz&%JH7(~dcCAM zfS)#2ld9*Wv#3Yv?}Mr@9&jd1o1xI7Wt|m~Br1KcDgIf9Q;(|Pd9tyd3RGwQ^8Z^^ zp)+?9+_T$;jKKJ--)mpBx%zB8rCvn`j)A8}Z#YM~`cz=cjLfGU-QHrUYW_%2|JGLL zvGtWB<#&XHQ@wp!Z@jL?L`Nu;&6U)@Dj=Vyy5p1m?r7^c{g9Ugvu)l zt(MOVS4rUsO8d2p1BkOb();0Sj0u4Y^&$A3$E=P{tWCUx%_F=&{*n?e6G|q;HSmsQ zU_=}5W)7A{vt5+~9SCdd(IdoIPRg9xb0%7gL~ofD7|Po0?RfXUZYmOvc~3 z`!h-1S{^t%)(U;e_`g;UCTFG(SHsvP=))yBaC7@WeNT@MT=1^@zzDyB4`le3|ACW% zXmIbI!cLUI2QLm z=N~HA+)>zf)w^$!R}PzmRQlnH07}1pjNnk-34`|Tl2rRMyO}|Ofe|5sfe9pm4DqA2 zc|9AD4L6UX7<)CHV#d^v1;c`hK5{$oDYW(Tc1zvX$G85%n zp3YZi=j$Hl4rd+bYn;~$f#`U4a=4(` z@6#bEt+d)PSlJimth{XqrJFW{#BHox>9Au6vvp0{wxu-}6L=~J7rv@C!dnlzAXe5f zd~t4RN*ul^v4T^{eZ4#iN+O^K+$bsl&mA?nOpkz?A~Yr%+1cwBj^L&;t_)9~4+o*4 z?u{+L80kFW7-cn4U0k(g1)TdbKY5D(s`QMBB&g(ywf9Q!*BhI0`Q)kh3*VFVn+yDU zuNPFuBzeAD?{6ARekg~X9I$n@3!*===^9z`h+6sXSX?b1?&r(d^@w)-l(}Xqk*yard} zs=CQcoWgr?h`8Pgai$8mY{i?bxt0+c*O5%$11B;%+*Z@?G;X1E4x)8TnyA*4FDSD_ zGa3}!Zu)*2kJ)ah#Jp&m{>`!u0B*qQBqj$IdNpGJ)Grvi5jK6G1m$vgi#8>jL#USq zJ@%-f1Pdj9F&?U3e69svR})z-Gdi`?EJjPmg zwx~$KN##tcIUus98pSNS=9XF^okiaPaA){rV0R;3NiY1S_*K{KDgWj=1NpmlE0_ht z(G4^_PzkdG&(!Xfb;(>IAP>Lo#a=cXOOx-w%%w?`+!f_X1x?Vo1({@(oKX-I>h8BO zxS1y863DdKwht&-vyIX)$IC7Ji-{G`s=yIB6^O6fH8(kp%}bdq+BjTIFX(m^Y>w5L zc@4CP!$*gB4YEPG?OUeO0#=Z^P-i^*m$;kZojD3t6ql%rYTJ1K26h({a>8d?EY6Fm zCV6c%?Z5tuGktQEYohggL&5k#$Y8aI6L#2i{21w7U|S}@Ogb}6q_&p0@9FiM!QAfm zNF_jhhdo7ssEg(0o@)(1IO2PIpir${R=YW=2r=j1BMcd9n;i|@e4tkRA%AnipnTD( z1jNfXuc<#9B;rGplU`UcTP4cl?Q;9jwk7pgF>GH%QOD2*;cZFfNk75&sjm**EC%EV z6k|#zrFRe^aT*94VqW0}PB|XJo5zWuweG=dOEODta%{0`Y}WN$L*_C*<3t-7vH528 zL_zA)8>hkgc3c?HJp<2C9~1)4(YeSjSOU@zIz=|!1J1EMi+d_z4aA3N)DhUVRe3|& zOG?&7kHysPlo-CHe2q}k44$);q;9W+Ua7}^QDT-V78DWZEI*+x-?b>`IiR`vG<7EL39IZPo@IQ{Ae*WJz&&xa;;UM<9wA|FuSMDt-whCA%wc8|^7e zYo!d>o~vFD>2{ij-uUTq#9pSVrP|-_Au%6pXf(g;TBWC|g@S71EiupEYEV}qcB5ZG zQ#OzEbpqU$+$*!YiIMc-e?2OcB>4WRH*0`=P6_m+cr(iPWj77=6aWXz(Reh#JOI2Q zFCgw18V(FrMA(S93Og1`6pGaKTK79^;wYUMg{^^0qyl(Y5i;52r#a>*y0S{j?GlN~ zGY6ZdhD9hX&P(q7Htrc;FsA)CGWIlAVO<5k=iGaJ2mL;IZ5;UR&5bdFwL-nA*TWPR zbH!p5heu2}t&-;PngUnL3&g4hE))PBCiSrF-yI9#o}s-|j@cY6@h8Q|+$W1VG_n>VCbb3Y29TG&QA2c0;0en+PAu z(u$B1T2+IwH!AITQ;v+Va3LOGT7hJcUw28q!&7>YJ|~ z>V5PL!}v@`FU#VZ472y+qddk~d$M7c9)%3h&bs zE{;P4s6*S-nHMy_&?4siJ;FAVF(rp1hxp|aOC4=A(Zm236BP-Z%YI2#;j+vgo@1!w zVfgJvg7q87Q_o^xnXc`msEF8n)F%Ll5*lnZK*FeEU0!tXTywc9CR5@6jK3YK!MMYs z*F1DZP~m2H=G<3B3#InxitvXpzlc6@D6M+%v?+<{F0+>+q%6ibDKsd2EPb{Pg#qtw zCk8!rPg)b{^f2!YCtXr_Z=6LiJUIG*jV}&|f^8g#GX$P#)IJ3+s+ifU)VG53ZB{oZ zjH|FUZLkeOf+d@sMTKEU9Eowu3~uFZg9nG`u_9Ex$?5^G`^yeKUU!7U$U}4J`6d?9 z#=t$U3DU+8is`dbU)+TW+#V}h_>$Fzk>D>y_Gd&vi$x1;9r}sQjFK&!2eUsSNp_`( zYtt9N&(GR@4i`E|Kl{!pb$K}#<*is#FsZGU&P)@VecaPC!`Pp}fu={Hr`>flEX0@8 za5k==0rRS~KC?*oOA3oOs~7P(Y)|9CU#vy?zF*?N{mp9U>8p?BzjXAGwD9z>u^Gzm z+(igqougCgGq~hL0uI#$6C%h31oQVRQLb46OYM;c30#67b$%{(-Q=uWn0jzBxZev0 zoH@z`P05;PoM?B#x9>b&dbm!QgZ&^6H3@69>T(R#NbLt7azs+3I1?1}dP$O0PkpdV zEtrW#2qgDx48|wqO<~DiA$0Lvbc`k1wf*VWdpq90IkgX-v*3Pw5m@F;vFeCbfo;pLqwl7tt<*9s-Z0h)SA(G*uu#XD0N4aCbO}%+j|2f~9=*T}+YSEZt zW@^fa6%Q3%CZlVp;0(3z`>xlr&0hr;Je--u*<={@^QH8&BXqKa`DcRVTT*fWXI0UL zS-AP;{=l6|XMlX=gn!IR7C~XcKoh(%P_ll5UT)*4dxi(9!hdvwl}4Y>J`l!TdsX-| zxr@hx-TdoIpv|eV0zm(7r!8gGn8nv_4lzu*uDOtC% zuj-Jl5bcH3d`45~GpFdZD^(p5LZfG9($ha7+k@1@b9AC5S;+}pZBN**Eb%bhfuAwC z8>2*itZy2p3nzBTs4pRq3)YecYLJ$DqDj=;^rWPB+S5&0r4Q^@WewGHbE>`&{NqF4 zpZ=UnnCIy%UPFOd(F%1;GCzMC7?wm{|mh^r-&zh zP2WmA5zlv5IDwr+%iv#F7jVZ>gQNueH2D_V)f@s41Iu)D%2T4s`ONek;XoO9U3Kk< zJ%BDRxihUDm|O#IXbNujfcG4mjXoo|&5^Q7RNCp-u39H)5SHB!Kxem~s1fvM>N;y3 zWj)JVz*pNcKe$TPR{Kv2-^JbZEPn%nA?@X%w~_=J8oo5$A*RCbE+g8f_r#1vDVXps z(cvGnl<`n>vPNVb*1F~20)S#P^yn4)VU_Hp%wyjg#wLvW=A{3YNJsr?fl~>b>b>rc zFc~&1JhwAs+&J$E_dJ-PrLOzrvF*JYqP-gPyA`M7vA3J>p82`-FdYULP2lJ;_GfU| z@Saih4q9jUOg98RAV7sLriCdLYS%s1iBD#sy2m8CL?L2FX>!aG8y09`PRKw4;Wt|) zh#zct0Opa|AFO;uXKhB1#7v`>dan6qkcc@fHG&&R(YHN2$mA7Czc`*zr;H}>dvo8S zM3l&MXs1!6+LRr3dUbCj>rctsgEUHZX3kI+tleEcL$Lj2esys3<0R<#L?ZA3b!)G3}Y*xaH$ z#eDDsz!XB$w$|V#I{yn6)x8;)XKcM6(LIwo_0c(iID7P89+=e|Z?9z#rSfoRc!CBv z>z?p@Ua&`enySh_!T&dIRg##*kCLDTWxL?v8smEWK4MPf0g?BBQe^=0BcRkAgopS@ zjFF6`sB3~E#w++FqY26+!2y`0_(Ax_k`YU&{{)<(@7>fUy58AF%()oocX8p0^gDaD z^7A8NtzB1nXCXGu{*xIuD@eRE`2+^`0-5x-B@O(lr#LHw$q&)7Qq1dH5pF;dIs8Q` zK<%p#5hOc>8piy|=OcHEF~gQMIg1FvKHwH>gz7%20Y=ZID()<`Icy#pO-&)jnS-pZS{gL>1Ov*kVn zW33ZRmp-X>fD`Ljm_fT!VC1f6I2J-BfsLmt&jPVdf8Evj7MqDy0phiVHU1B)GkV}F zTVKE=;tcEAa%%`3WG`SGRz;%LP@&^X*5#lm+y7MX4X`k>_oLv;<2e8jUk<@wJ z9-CkCi2!2kCYh%9(obphG64FXsr>)t5TM|z|r8vf24WS5^n z3ek`B2-9Cm;8#1v86`~rFSf3q(^|^IYrk!qLTDI9j%G#V4Hn7tj&~>4bbQ9?aBs8w zuuco~fqs<1iC3DPwl%Ut7`Vxz`&EJa>}$T#gC;?s-xKmCDTf@Q2}>NQ+#ZwNHu4!> zI&;DRKN7Y}Ywc-OKw`5QhD$o^%R12T@H@jCfF;XFl_`3W1=S(RU9`+Y zp^v)AFsx>0fspdn1!cV7hsD^_JZ!Wvv5Zm;Q-@(syWVkm?s&VQxK{#q=J-jZOQm53 zZPdBXeFZKv;fLsjJ9;h4E;-r)j|dwr{>*ch(PZL!6iUruKMNx6!(S3q>lu#%srZ>e zt7M>kX3z0{#v?T$GxD7Akl)+jQBm<^r4f^jQGxEI%JHeSXSq<9rOrDY z>~_38MBK{H0t_pT7~`!;q+5#dpQ6B8o*(5 zrdR3*@_!%;O&$9_rEw@IvJcZBiTm)W5MfV2=uvT#BR|MRax=_onoNd?Hln0cp{R#M z*|~S<&=l9KK)XPd!6dtEba;!->v+*xaT2K==|&oY(`DEBbM+QSO#=If^4ktok3Yo! zw$LtP1vv+hF*Z7#{rSk^319Agtfn+K;_s`e(xWc~#``XYl7vqz-;DvN=^kiJ=TBn> z2PaPxx&;N7j#ef%ZjP#EPHtxQCT3quY>ix8id9z>FqAR%V64NCRcq+o368c-$X#B2o#Np4IiK^>@-feG z*boFl)qN`ktPV6q_@py42R~7TGFR5OA%?gtk6AGSEl3>5g0ynfm@ayPL$n}J`)HFyH(I2C3%d}$F%qrZ!`WSEk zBG)RC#JbV&E7;6*LZ{vLV17+zjh!X2 zs?S7=lFi`uTg)=h`wYqThFfrh^m4~0kcHSa+jxD~_Omyh-bJz2KTh1qH&>3OX3-rr zPAil&HT%)~WYQ$Mo%OaH{!L%|JG6*isAn0y0DpRZ)h(7HmVJB32EZ4fU3%p1N;7!X zR1xdSkxTcx&uAnJG0m8b#|i+Vku5@vaum zPFI?ULbN)jq?+dfOZ;5selB}*|CID_3$J0E6ct2Az6oo>Ag9$G!o{^$Y7$RPAmjq) z1&U5kN$nZ!RpZx((2Ovi@IJGscZbCE=nvjc1GQmul^RjVsYg z9OtJX*eb$xtXcx2sII=ag3-KF$Zf|76sVwe%$mPI9*AQRlg2ymjz1R9w9D!%B2r_^5R)(z|;GuSJ5?!_EnpL%yyZdGejW%+ltjLD~Iw z4~zPqqtkJE+hMcwXh1FMy><@M?0GD8urK8&9*NsZF`@lO2o426w*w1E7hdW?T4jqD zp6^LUq-sDsni9rEZ~p6JN}0x(jqeO>`N4P+e~zwP?|v-=fH zNs=E4Z46$9MwUjZjAqy{BuovU6%tvQeW@goyOW6+Q}|^IEvWTelA~`XmH6h?XwfB* zY1#)EP%PQZT{c(o*L&0BMGA#{=AR)3Qh}0sUM$}%Deu&y}C~5z-6hx`wLo21rdm=c~{fdh4X4$btyqtbCIR4q} zdV7>vPE$~_jcs2!Ojb%Z5fn-wYVJ(XuAlnXXH}ux*M7F^EWl3O^l{{|Z^ivLldUfB zMu%DrKTFLU2H-8WZJxjj277HX%eBA%Sd<;WR%48exIm*rvHP9n(^GUmZLnf8vuSZL zj$t}OYw3-!fP3RU-F*h6-k;SDsJxk?6xl)o5lxaUP!3lu>^UPISQNfo)W`(3F8)Lu*3&Z6%g z;3u@vLNwOnSxqw*9SWi++D?ca;>l$y()+2t1K#($fOxiwYZXlxSBp2mM0~Xd2cC1k zx~KLbA%#o(@BOy6GD8~8@?{sHvdQp$qyj-TdofJ|FfD4?zKNC(x_RBJ1qBy+btQTX7u5b3n>3%0QgC(eWUxU`UjE1ipYvD7W zr@e-5%A|*Fi!F>ucT2Q((`S*;6n$zW@|DK~_`QeQ_ER-co0*M+;(n>l#>A33z01!= zck;4CJc64F1Ws)L`$_-Su}bS}Ea|f;Zy`@Kl)zTB5km4^=*OCP&_O!asCUYTvHy~xq^1XfCo zOrrwHR6ANLre5+*k%{uC&s&T}{eSc4GJeSQ03*dobaJx3_-E@J!3z1|wIzK`3T+yU zINOEk?#%cyGc!u$LAK4Vq{dIbVxR2`=?XrcbMr4>QDFCp4@eS>uol64&8<3LGnwNN zYCpxs&*l^_h{uzdNq}F>NQcB7EE7kY174`rC3gki^%9EtPii6q7?c4dbqg0zSteD; zAU_g4lrbNk-4L74PDv#I=&Q=X?@$cEDeuoS1%o4+1bfDyCE4`%Q9xr~w#pEtCGn-_ z5tgOw4$R810AF{+VatdR3#RYeM>Felz{2%&r;5rrk2qEyF9D zY!7waT1k^r=;~$N8Inckp6^!iiJwQsjj)Af_v#1F1fPA`{8Wg-+nS5v+y8ON(S0aR zbU`yb?7d3pV}=s}C2SoWoc}w`?Nn!kQ2mkPlkvo&NV@Y1V2kO{j(NjHbo85wm*)%o zkBW}a3ax6AilSc;-a@{+VOl(IJ}eRMwWc+x3;;}r<=kC-S|$WKJbWH6um5s_EnM;i zib19o;`XKp=nlAI;?+nqlMhs3jtCG8-NM?7Ibi@>Fjr$m1_-S>@qcB{Uc;YBccBjW z@hR1n8Ajx9*cLHNED#1A(1!&Szcn2>;Cdf03|-;iw(qE#h2|!gIfVvP?OoiOca5$k z>i-x)AA=Wd8Edy0aT;6P`Psx5>Z;yaGJnItuyFlDeqqwLW+7=LBP;WBMehPl?qz02 zCh0NIZLQo(Tfz3y*pfcNOb6B@R`|Bn0F%QbSdD!4mw92yQ|IsIJYK30(?mTPuB_Ay zFO!Q<2e?r=Jr{zr65F+FuC^~H;={0DO{f;nj9dlN#PMTCF(k@#UqqW|GHZUNF=RYM ztij3soNjRq^{j77_fDq$>ipXhZTEJl z;$fK0FQYGi-IHLJruP#QfI+tLsV;@YQ;jjA_yNaADd-i$gUA<5$O#02BEGSxm89D)p*`+_(ZJ?F zS7oA8lJoF#iexzofqX{nwZW}(rIx8TfTYNbP}tF-PnlN3;1>sz3sEqh0NT+a-aJS6 zE{Y+ha0JuuMHx;Mhc?)k-v*gNWR&)C9BD7)n_=ZAEAz%wm;m{dm){CqQ}+sXGPf6k*>v}XC0cbvULxX`yeuNTfOvvEaX-a6|@W5iVHI*49)K}z?5+va!l7c+4 zg5*FkvCk^c0V+83|?)DvjZe%2)=q$3~!fk?c++%f4Ub!0YPiiSn z{})CgZrOsvYwbwklo-uWJHMh)!e92k%Gl%C;($-$MlOBYw;%n@Wft2^&uVoys z^NZ}bp;5(4H!9|KjdcyVOSX8$SSqZQSxa*E%sR{TO7F zJLQ1~c>0FweFW3+`|PH5c}8ejNZhpg1v-7~w5hui`v2fn=*h>Jo;G%wi(U(%`Th79 z;ea!CedUMZ8$YsTjuqnw;__J?=Zj30I?azpSS1Vf?*u#rYQ4P+iSa@rekvFr)?~{` zX>)Z8W5}H~yY0tO-l||G^T^DmZ&$CTQe-w? z?&U2xR_pWPaaDNeE}IU{4YOG-=wOC^LSlOkVdlU{+M<)A>_%#vb*%5E?_e1C{Nt&X(1Q5L-GAPY5Dq+A_ zzQI#E!Jg_&CX023GL7i>c18*`pdSuFLSKZRy(S?i#vuPY+z3@7BPcNc7nijaV-B5# z`<3N~i`#ZmmbI2dnVL zLW=Ys{(l|Y|0I!Wk5*M}K$D3G#QwjNX$|vZGU>U@sH5`ZP^U6rPG_PDz(ZPE65!BJ zLnfi;$wyx+pHTb=5v7&e*KTuyY^ae;?3+w`jlF{CW%Yt(<-4gzc~K_38&!~!wQ!7< zT<_@c@R+c6D|)&YJb#5`3MqxtRoIM-CH2ker>Qx9fHsjXVyZ|e(1%3Q1Na1*+a&A`$B%)9Gf| zC;Y+rto-AIwfi?U%MQ8{vOFD-=Zi|C` zd9Uv@+E_46X3u-9sQh<_%JfZ%&k&K)#7+ptvW|E?Kw=|n2$34O)2y^x{H*mizfSAT zx7pYVmZ7=HlJ=kHQ0u6bv2}A7_5|!Lp&3T1J&*p?2X+eYCkz(6hgYEoG?cl>gKGqDumsK zQ8k2R=E23H9!jyb$)-n{4;{|_jMJjn_&<&(d{MfsZ3j3QST)3dV@tF&?k50R3l%Q- z!26C}%P9by=sh4!Lm~i|co(P4HwEin`&6S+^}@TEq|=n*1JJ#Ya8fdq+` zMCRxAtvZ_Sj2%7#R~+Xa<4?CRyEv69+C=J!6<_`T5U0pYoH)Zs1mV^k9_3`5y|$Mg zti1d^-*^SPfc00Y$6;m8?zKhC5y=+OwzSIsJ>ZCUy?tqw&rjY2WHsKhMV#2?zI^DM z)JI+BhGMK(r0aC+RgyLh9*!K+h2X*tPK_(b>+LTHq{Qkl6tA!9QQyid+oo)#<9lFE zb`*$2p!>3&7?_6D*{k&3?F5Q-Vlv5jwNw8JTW;a{7K*d-X;t&=FR!bZM^5z4-(M1b zUy&h9t+*fgJOId`%rU@rHi^90SEj;rE#Bj|aY6@e_a^I!;-#+iPbIe79yqJi46WH2 z@jot@Qyzq4iSF8#oHqLi{&T+{#{22}a(P<;%}BjWMmVwpZIQX1I=J7B4m*SN zrpL3ojjHhm=|5%t!NayNl!l(eBI%6?B`{!;Nfnfp0zh+C0Hxz6J--E8cXZk=ax3D@ z7c>Wz*!>elOsF~Y3SCyFmL$zoDfz9Kn##JG!^%Qt$+xF;reu< zQ)RGY_tBRdR!3O$a)->9Maq(`M?#ZN0ju_}3{}U33NxP*$FIwB6_hx!&sZ*@6J}bl z&=@^ICEQNTW5B5Hqs1nx-sU!5Yd|hF2a;XIBaefVsu2JvVRcnCs9`@RGotKHA8 zWMLo26S#ue;@Ld8UbE?gB)BOV`s#DyP>{7^a9`K#?L8NtZWM&uC^Buv)ZjmILAcO? zz?1B3tWB){BmebutqMtWrQIdN*|K>w`B#_iTP?$un;M_J&$Q9`+9yRAY{(7^7i`3p zc~W@I4!1SkTWfpr?zWU5bUlx}5fOmK1`MUFOz2jl+%GdsFdAY1Zp?GQK<4uM3}(*5QZ*C-fTD+Bi&8AjRQN@w?x` zS77fuO&%q3ecf!Iw{?aPk1q7Z2V0T74vdF6zLJC6nWnc7Ldy%eE3Id|M{Z#K2>uHnj(cgNq6ABbv8p2 zLb5GH@v>ZQrGO5dK$s)nja6Z+zYultqDXhalXTOUm&jAJ_!9S|MKr#7{p$X3RqXA) zAE}Y^a!`LsqRAApqSpX}Xv-L1^{IXsO_P}ls*D^&`a=H`Lr-}4gSC23?Owh4$^z65 zDqpiHaeqc+5N~vYQNP$^KXN5bIR$qnBRLh}A0Z8N$=*+DVv&O)EY72*XgY16E?{G& zvU?JV-?^H#k%Ll{urm6TM9PzpvslKVJUNKPxBILz@>9P?uBNGSI=mIRCQ+C`bTu+*DnSOl-{lCqa>;@nnFhhWUm}|D_|E zhDN4)R5H>Mk*pvh^HU(MfH4;Fl8I)hnW4MIN(R;sdLPTZ!iF@hyE-`^OR{>+yN4SW z;MebeGBOB5&F&zE4;l}$x$kq&xes!ECc2)VHiCYF&+dQ1YRCghX0sw?O2~#5YJmm|B*i!OYsn`ODvbkpBPuf{%#@UQ_AIhK1+&x1 zv2L1VS`%!p^3sRa6TeIoh1K0@_^qs%%4IkZr8Ae;7=Iid*~>?8C5_av*(?@il@Q@5 zrK%~JmQ+#U+NrBAq^j6GZwrXW+-98Sd`dlV`aw>rT67v=x=bNRIhbcH@dV^qlIe-` z-706EOa4)%yvT8^Hzb+-R{l0*3^zBG>_gX16aVQdSM+Kl8@A9;Vt0{40!8h=hCT{WGC zifg1^pI78!V70I>Spgo<22|aQK_)PeLLz|Sgq0YMNA;bx-0TV}$xW_?x!mN6vKxNe z25loxzu%i`VT!~UBFQ1cRtzHNE!zyM9!@dx0hu%KLBC&q75x$d_)N1+eS)-Yf!0!= zG_pl<7XAR`A&$u0He|X;^rR+q>Y66m56eO(;bhS7ut;aP)|3T|`KI=o#cSO{NSnxx zro?}1B823hsKk?@;u2qIuFY|q%pCG!G~xfBbj8*X>1C& zw?oi4z&XxmQVBhDugbkbTHF>vrrg{c+n0C6=)}2p*ZH6!C4#18#%yem_EbTKZ?d8k zdJl7r(WZ1^UtJDp#^L5GO3JA+=i1X|go)xxHjkyEGk3y)Yj~qP)idfXF;Ip@qk!M!ag{>^e69%bI~#)31R4v{!ai*v@GU8 zL+F8K%uy0sSxP{7GaGA=N}_p;p*yr$^Vi&81Ui{n!s55Y=^ncR`xZ)G6Oo&=1#YMj zHDX}b%7HS#WYyRxnx84jppuv$8O~Pue0M6)VYII_W_3CAV!Y}nLKsfqzwL=^svQ2s zaAz3N;_-(D+AId<#BP~q{x&hbg^dim9HzmBwC}(*+9u&NYQXJ7)61UshpeZfUU>|w7xaVyN!*;+vtx6q-Uu!ah zj{^p_SGez}`R)d4Ui=N7;EA7Ry6-0PX6k<)R`t8Dw-suNM0sPlc&(TU2KITn4ioAf z66#q3V+1(ZqKid?l`S9j0!gMCY5KV7^MK=Nn|wdY5M1LKmH)P#L|AlSC!((46RQ8;6@$=+QGz4S2I{cj%aOFZ1Aw-y<3( z!yI4#qa_e_02eJxN&S}$`nSB-Vvy?Y<|1bwLXl5GY#yN&hSdXXFu?RTjXDvYP1W62 zYaA-SHNY;He?~aSExZtvjj#vWUnB>z=%qy6QQKww^c__O8z|`FGX0HJW|fm)g7uF$ z%|{#@FAPH*97LZ$1OXyQ5J782~C}3r-7L2AIC%=`z6b9W_<}dhgi00x)|= z!qxw@2d@6-q?@Y%wRbt_(h1U3*8uMyQAo2|18}`#;TnMN9k&*CP4QciM9Y1|L2PdX-QlE zx!jj60Kup4wn;{|ifJ7Kc!+TC^-dpeYo`IX0a%|9?9)j10D_>mwGq-bw*l{8kVre* z2KDiEepkq(sqX+VK2Ev=64to93+0o3x?rRo?Enx--bdrfA`=6J&|uD>I9L<3$@|}* zq5xL+|2BtCv)uj9IDWgJaVk9jf5jO{@iC59c90hbXdH8p8>au?K|oj(K<@M2-1hx4 z;`Tt@=ltGz)ztm}=_&kenwtUCQvuZTe_w&uw~v-d@!w$5V)p-Yds+LSAqaxr71C)x z2Jp~7&fc?1mGKJ75WIoPYQ+E7*%_lj|2>v8^8*0s`xQhSfV#)We#n*%0EGWvAJ-jF z#qs=MY41H=qY3XGQWO=jfC?%o&5m7zEsA3AVu>bx?Ip&7Ehu9ziM?Vhv6rY(W5bfz zMUBzev5WQh+1tl)mp^{~;k)_F?Ck99?Cjp|9vpkeu?n-Yp3h9ChxcuU5>NoosMI(` zDumVPNph*VC|@?K(_CHo=8c@0uM7V(Az~k~;PSkdh(xC>7?P+I;%*pRSSUbtKCd|P z0V;k&4rSgn`GGA!ZqAN#%{C&KoZdi7Esd7m^A+h24-f&+GXDv*1TO+!f?7Vb35T4s zj(;#44!H*{S`A%g$*i~~#;jJ0iqWkAy9k8ux{L@OiAL=7!XNF>)S0@3>qZH0n)XEW z0)jY@g{;nU{t*qjER-uHajtG7IZ{Pmw;K*KxP_52wM|t^{a?M4T#hsk0YHB`soJ&@f>vtxr#q*MM;F-;x20jxm9Q_Q{Z&4VbvfgtIMmLW~&HtL5oT4>)2VPWEWHtHI zqzXoe{U?GeC?$CWf4Pd1k!Ef5($aiepmRg&oNtTDs&GBv|J7I2LaxvACiGROUe6u9 z@Z?omuOH#Dcx06%rDi@1I&sOGl>6M~9n5Vkx()x|Ky60OFKjJj7pU$lJ2lX#^S&#q z+w{UF$&%o@o@54dDjqeptG@KU(D#!I;Sm&d@9X~9c}hA*ocbsq}T+racxjfTu; zkZes6uS97i`am}11$lWnm*6)}4JJ)4puVrc-(AGlXH6^cr?l4&7iq4oYU+u5qv+H- z52S{#ZN-rXFp%W9dG(HS%TmZ2VMfI_s3x{R262~APov*Ba)9Qpp{9nD?+e9!=rQ!j zu2b%dp|YA9@t&VVmF=CK{rEg&5awV83uGU^a9(A(>-n&XeP;`FY3SrkEj*lS)53Sc z$h92p#$>b-Ez&#t(EblLLrIY|i|!6NIVEdq9_Q*PlI!d2Nka>4-l05bimoC!{U;u> zbVUVBbg#hXFBjm4rOH{UriNBVbpd{MT0uK1n%C2u4QUGhWhpA`PuJdy#y)tD#;)>l zu&_}r&oXU406pmEKqDob)WQWuc_ESEBH3MT`8#KIE(j&;To}t~XO*L48uz=2m>hyM z5Ua5uJU}UApaCCkcHRfmKBB5LyNc87lg*nh2RmD7#C@Alc1hc&Q@2M#-%xCR*VE{{ zTwGf+oa-F^2|D|RX*nMB2NcWdG<)e9b?K3!5Z_vt145S9Y}sh!zlu>+lJ(hEjZLpf zr#{7t%o5Lu`m~)BgX8J;7h9C)oOoxa?%jq)emk%?B|A&SDXE^b zE9I1z3~YD&+!QH}-HWGCy%aEau@u3i1pZul?lU}hke^FYlCxBvEp-shy(B#?at8Z> z1L=6#*+lO-QZ11eE=2>MIO{2u0U75&@~lixn>cdPfqY?773P;D3XBbrJSg1->@)|` zybO??99bzN0rb&Ds>E(3@fJ3s|G7%h?5|`_e8)!A@iK;X~Csk(Kdkf+TCyf0$(Szk=2=P67sXEKWf|Q#* zb%f9#!T!PWlKXF#LF&$uu%vVlAvD$|6{D7(sNNszJPse3=3JT#-Z1+FhpS8!@U2X= zrlA?|o*A0fBu`QV{K?fD>Q)<3?(q)-o3duF0 z4=ODd$jz0a-U#NjR6!gS9XCVSPs;?{Y^`&YyuuP)kzxTa=4Zj1YLV)&%$0(O-Q?^` zCwafvtdJ?TNx+Cd8(rUlkQ-}7bS&7dg3}Kp8GqsMo;?bj%DV4Yh+ul?B{gIv4k<_w z4fmF!*wMoR$@P|6u{kFcww@ZENB8vifzldh1iarzYRL zr>Lt)>ZTy@{XuzRfwNIy62bI3X;mw-YG;7=>yQ}J?{mQ9w4=2H$DjBR)CbsW;oGp zyA)1m-#Htpk4>t_+}t@*k#5-#yBM4@k!xXolqSK*$~pznQNER#=`@Es={X!p;dYFc zTb`VVp~b$;#@SXnYL_JEp0vdV5lf&{lYO#skvKYFVIR5-X zQIth;UQf0-ivL!j)1fHPtgXtxjpU0?>9USQrt3t|@1hTQFf+Vx6iGrBX zfZ6GKD15xTp{6}awG;tA8Xbnn+F3^+{hBZ@+05)xQV=_YYazUCjY}antZ2wPrVQnj zl9E|^6G2$JFgFS=4dg{L6*8kVS`yt-Ao-lw)>_5x)d_~#))qSBT4#-Qo!cp*W?Iv* zQ0lv`8mZ4;D^l)MJ{)7gl%_&vhGXJO?!*yHEoCJgJqnkqvea}H^05~SqL~5k&!DpC zj?~Ty&qOQrc5jivj&t75t_rU%Th~n?Ow=nvs_s0SI)`JB?v9XJvJX9|b2<1arW`^t zp(iIguuS>466KdeXWe!X!J`n>?aNCMhG^{6bj|1=IiNRnj?zrw?RwGP@@UHUy+obX z3Q%y!L3F4fRb&N)oBW?kLr+#l-swS=DnSQWCMs10_H`RUEvjI8h#$#+ zZFF-Y(%A6kkiS?3o&5J01=dmKWM-siJHV?D4c^1=1#j96D9eb3vIWxxQX?BkyD+E*GY7_?jv zX;l#iy;lmtu!&hIXbwuBuZq&G*9!PxHLTvO)iB@=ZBQZotHFa^aug(p&UxGn9>%t(<>zX37FDL>AsvL(Y!uzT~mfdHbwEqr9)XX?& z`f^i&y(u;hntpw%(G-7A(d0^zH4ubgZvaEi1sDGxQ&v67|4_enI1tZ zq-P?!u0;tI@+rc_NM{mJ^kuk!(_>sbX;~!~9jys3w61!Li+XO}UtSRnrpzQ1?ia1n zc|8fC>sMWcBqmGIv?EChrcrfWtdyQp=(S&x(d-_{LNuwC<1N~gwv%9;vQ}JlHeOGN%B6U+( zCi=olCiYVhcWPP(F?4(gN1C%6Lj@Z?_9vc;&jzUw=11qmH%6TlUP$Mh#f_J zD7Z1$U;b4Pck0_1K{NTOqrgYh8ub>=yTS#{uN2sy8WUPnuL*BIR?J-E$R<)_wgc;9 zPPBD(wNcZF=tOyhnwmmz`4_>f-4v~E<3e5?F?}p*iV8>R1QF!rY9Zq;XfD0b_zBpxIrKaa5Jacuct=VP6vY1KQY{u2B8dJiuqrRn z0xQ}pB^9J5`=*Q_{Gwd_DDOg{*(0jBs)w#~IUyC)5=;I0l>{-SrPP3hR85=2G^ICA?@LFA@kHapn?N)t{hh#OT*L+Rt^ zRLJNw8$pXYLgJshoG3#dJ0jZ3Jm5r0YTpSXrR)h(hlNr|@43;$$x=-r1X4^up>UtT&u-t+QZ^?BnJqytc46 z%+2e?VTsQ5hJU*D6GTKG6lga{5Tp7aMO+vrh^W4Z-7#Ze@Yo?3@9+CS#k3I$uLkoQ zCy1MUFo3gzfjXxv6t@zYRjb zyd9nn%0Q8+IUEV0J{cGX7q$uFR0jOiZI2*~M-ZI}10lP0pFrCGj)+*sk!ptol6L|f zo7k-|M$B+FyM9FQ8VsQNeX zV(dp1Jo6i5n}^Oc=o{EL)8Ot+YrlmTeTJg83kCr<9*W**jW>KQ^C18`M`JS}bDGOc z@fC2z;_f~?LpoA?*FeHfVk}9N5c~~M#@2=>s z?$4ysDygRxQ7P<=VACTxY^VHh(e8^?1kva_4E<8o1#vtH8s%B=#CNDap(ckVx>d*B zN|xbJu_jR<4I98wmpj4GM~yU952`H$)(nR`O4Jv`=iyi$-f2iJMxpl4-Q7JX^DFn_ z{M`l{nr$@Yn>Q0u`~L@*m-$K%K_jFl>|txAybmqwlH@UpWQV|+NUX^679@F zE#4#1oVC3a*oQg|f*ETTgExfp-exE~585&kfnNDrjs%i%6fBuMoD-e-jE&zQIyKo{ zqW)D;`r{~+-ZzoM#VKaAl)_$45(O8HhMVtB5yZREQVX^PZ}MDa&oS7(89!SPm&Tw2 zmSqVddMs*wJeO{d#qQ?XC2%tO*AXs9$D*bQ^Ej_Bvo7Sn#i{Q&EVDK(7DVniEa}pg zD})EdjYl^Wtl-Kenl&EEzrhPUCmxJPIKAJ%JIF>!6VO2~a|Dsa3ASAj_c-CVOAxUW zVd}^OwETO#rZhX_j?J3m2-u=`)WZ{D;+mt1fDfJ80v~;IUei7APbdO4?p3Lc2fbT=meZ^^?;jhpw?eGjLjff z(^_9hV}u#ACrWMIkdbGC zqg6E(HL9qR3Y>vec<;&r={Ez*q0LnlLQh{OdYJh8N(9r@6tFeL!<9DGfotMt0v?d0 zz=5=sBfDxVh@PI##F`?zK1Xa+t+_|2NMiR>H5T=6ECkH0JiKZ5EGP+VE|4#?5F&k2 z1>u?IVG(0{$ZXzE9R&Qa8$5zHVQg1+63FM-m>kFT5X6`f9&Xg}N3?8VUlnrjM`Vwi zgB2t~Sk^WRnqMNraD!1ajDGr7@~7h*o`+3C4j-6;So-|R!-K5PJluJ?2o^L>;guCH zc#GzsNXQQg>`VX5!N|5{D!Se1z#O=@>0FdwI#a+&^E|BL^|ZlajgQXE5ds;D;e?_c zH;-)85z1(OXpr&4Zf5yHrTC6NtsP^I+JzgIZV~lve69AGSF|}NPm&&MMT?2$M}x&M z>-q~V&qB)=^OwT+D)=MQnaHvP-QUHTIpgCMYkGNaJnDh8656xRl#{nk(JN-DF|Y?S)miNOX<{UD6qI9>O1{g{%GfZ$yINjnqfavd59V;aZ~?Dgj`A`l>G_-?6{8vG2++i+8hJ1X~Q91DE^Ga_nBa|Nl%q*Oud>7Xk{@hjkm z+_nm0pv)DBtkezyd9(sK;d&=QjOwKeA|0-Yhz*QseKbz->LR49tMGoadnFq6w3mX^ zWvg&_A@|-YES>A%m_oL26&3)8zfr_2l(ZV_j$Z#0$o$pFKbFyg$eE;*vNyqdp=;2_ z@e>5vdJQIz1Cs@jK3j)PIKI;^?@68Kg8rF;w{wopo4<$^E??Jzw{C{ubzBQ;OV1I+ zu|+x`(M{8qX&X4tA-xVeOg`)2)=Tphq!wHM6DRD{biJ+w<*kET<5vsh)@F1MzfC2~ zs=FTh+%dF#9Trm~*TWluIkbEW^2Y7;=-2_<1QELdvx2mX6QT6wqz?Oi8_+R6`&Ec_ zBTBbEtRVh;@7PL9H==Eok14Q$+H8`rgSZASb=FPb-8`k`)n(Jp3*^8isXmMSOCdbz z$xWS}ZzDSV)?_ovZ^haLW@SIt;b?3#j2?1R1L&w=Gsbb7zY9?xZde3sdcP1b(e4~b z41Od7WZnWL=bs8<#9N)b1#G1rpEVuu_%#=3#ab5#zZN*_ao<2$M_2g;rj7s1c@p*h z1#xuGnU-$_G1;KU_V6#TV1gS*g2=WN-B(i2i7?9G#6=?~+OnBehr~9d>=<7`4A_Q2 zxZ9r-c1jCDwKy;~lJz^RZtiTu>ZXKU@B+3YJ8ll47Td8W9$Je32Ghyym|J?6rOrFB z_$#vmOIq_RQ@vxuWY@1~q!1ny{6DndX$op9y9XvFd`qE+ zA$V&HtjgGfhP4_Ykhc@`Ce_K#)gLsrrH>I(y1h8S?KMsihN&phrYUsWXKAFD4h-K}h8v*1MAD0Yub`%_^k*0ccu{V*_rL zEYoDK-jntofNQ$`s)F?g0n6uM#}8{NXo_&a1iB=9uUa3gU~$&S9cEMooeq{ zy_x(EVRrOCrXZ475X?HnuPfkM4;MUr2z?lKN)RV5>XG!6MMJ~i;H>Ls1aHD`$ihFI z7ex7MaKe%%aDtp--Cz-O|BLflu|8LXjO7j@@5}-?U3#Qx!m>L;;Mrlgf67CJFpz&L z7Lf1XYoy1%PzgkS(93VUjx==m2lCu(Z}kTCpcv&$EsjAd#9;8@OTP&AH{N_WlKwl={dAK72Xp+Wwe0Vx*{oN12`tsD z5FYfom_a_y^rft>}q!fcBQcc3`TJf5%MD%o^S@qc|so{aP|z2{VNVJ$lGa-K$?FB z8oFmF0yxneB8Z5y@L7*xf*5rc>G;ubK};WSaBOtFJ&V#2BL!R`7cyC61TiTW{q@U4 zLEOkif91?j2m{5R!|XRXTOc#HB4*~EL(1@6qCy^@g8@D(1d@0j3$Z8b6t-RUqJI25 zthlsE@IIeM)NKES6Mb0cojiJM^!o)2;gG$82)l@d?jgKmaL(w9FggJ*6`aUBh2TeD zM6jWFv*5_Hiv|OQoP&Mx!u9w?O&2xAD~Cf$-WtT2$XS8h`V-;e{-;8?()t_FE$_~? z{tM=w!i5B0wEy3R0C}fC+!NT!dA;)#o}Ow=#MLBm#CQq3cmD|9{HF$Q+8=|k>BiwU z4;=6%G_>RsLA6n z%``Ve@)osEz9LC3r<^>g($6dapOZ<6F7@0z$*Ytn7TPvXyy9M!YPj@7@-Bib-kv7W zW_vMDE56bwyi~i~R3zp>4U2g?&YsrTG-4IKio~oGe@%*TITIj5;WQ@H6N}0kaKM&p zuxxUmj8_*>vFm^~gvbz5%XKN%B|pqTt-mf+bJ-N`pj>W9(JqtAgNpHtqCPiJgAO z0351b-GZtUB??g!#oUIbvtfmRCr!T%MSo&nhpWDH8>7S$C5X+{jdH8 zP_;is@Mhk@I1a3%2)fh5JD6<~8mW+^zY#WVup7fQH|uFM(TcyZjMleQA^5__O8Id( z&YJMNbkJJA}u0D@_AkH26Jvk$2G^sh=Xvaf(LMT@UJT5_yMTs`w&%b+pU7r4jcXGG>2pME3g~c z9-*71%N()MnY##>fsfF<6yzHPInI#^*A*m?q8>v}$V~f|b^eLM+X0{1Cwr}9R$Fl^IIo}jQY4~bZ_@~QT)bVn*!n4ulw^&RK#zhC-JV@g+ zigNa16!{Keu7Dzk(#fF@j{^dp5;tm7n1s0&k*5UdB zC(i7GSwjm@k>6$&l3Rdmo)^;3wEO{){5mg1Mek2s2&zgdypAUO`M0`x!Ac z|BgUnA0eh5Ju8fX?!zySOeHArUZGUM6OGiEe}q)5EB%Ea87_A0CczRH94xgX7eavq$!-HwaWxM;zvOmeoH=Dx8|$@q3cTd!m6ADFd}ty^(D#96b!PDNg-}V_x(lluneXok>#l^)9b^y4cE>g6=C1b2 zte~7iFNrqmXsxR~f;FkAfG=F_I4-TE(2d;e_1MYE3Z3I-ugbQ?IOrHQIGI0EGk1G+ zwyLiDT(7CwLOJfx+wvGF*jdP)sBui-NSVKPqS=d&KWtx& zlYzy0C~7-ietxD$v-?ewpFbPyp48M}ufeuYE(DCU*)iK8oDXwX;|{8|GbYkxvF$=N~9znA^c zO{LyyggnSz3|@-+AfwL$EFRRa7`kKa=OUoFhb2&z9{TDm>h$pZOOa%>KZeasBULJk zp(`t!?2lpI%&H(r)%cSEB5Z;KV9zcug@>!{lEqggFqsRu`X~Y(wBByPwa);AZWCVt zTlu#dOC`GpeGJ6YEjy<0MmCfSD)wK288+mpAMwExx2~w%0~;J*Dy@Z$R9`|IdXvt+nBArLKbuc6{?s%^o( zaWEROE)b1~NK*0c1tRV|@xhUzsa|m)H)^YpRmD+TL5d1-4Fb}mu?jJ_vRG7MF)j!d zO>CzU*cXIuY}7%8yzFN27G{<0sp);ZYZRF?FxVc;26k5ve0>;<2L9DkAR!_4`s{IU zg>9tiA+T*oKY`2|W2r#aP^8Cc87idhcc>aG5-Uv_uBqBMNF{Y;I3h>Bim`r_Myk?K zmDJ}^79ZMJ0ygCjQ{XCM8530!6KEJ-J-ByaiRdDecD0hIvOMc*RAbFI+Ak$9~#Frl}dKys5UW>KI4R_84Vxb$Q zP~ggRf#j7&=BQ8_9dm#b#FGXrgQ1t-!8@x2`xzZ^j#cKN23cJyUoVsu%^A zz0OyVTI}o#LEMT$*BW07BIgtOuyG~S{`d_?5XP14wb`-)LEs~`2yqAVimO$f!8?6a z1iZ-VhHutRRYp&znlw^ZT`4pM6KV6o_)c*wcw8!iJu#}_VpZVNx)v2OpbApLU*0NY zq}^)aMIDC&_o|?^IAbo-9TJTcdNNHx+-ZEYy)OF+7bleZ8}zeccb6-XXEwJOD0$zV z3-n;W_u{`%G}mgw&2@x2hxP?&!pS2sB=*)y2*P6CkC*rS=1uV-jPLQ(Uv%SPc~_e z5L#RVt*y4$>LvdX21>61{XgO!9ajKeO=g}ih<7zG<;E-&^@PORy{S)4EEg{0qZeMY zj7(i^^`q-G;hV$D6}U0Ggi|bsj1NuSXf>%WlI@6xCwi_{1ia~EJZfFFPC;-{BoVdA z3%B73kdDXM6IX}t7O~Dq#HWw@63_#2hqQ1kt8sx^C)&%H&$*m)>Dk-aY4<4`c0vCS D`zXVN diff --git a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java index b37935c..a478486 100644 --- a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java +++ b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java @@ -189,6 +189,15 @@ private void initSDB () putConfigVariableInSDB("rollerGripper_RollJoystick_LowPass"); + //Game Piece IR + putConfigVariableInSDB("rollerGripper_ToteDistanceMinimum"); + putConfigVariableInSDB("rollerGripper_ToteDistanceMaximum"); + + putConfigVariableInSDB("rollerGripper_ContainerDistanceMinimum"); + putConfigVariableInSDB("rollerGripper_ContainerDistanceMaximum"); + + putConfigVariableInSDB("rollerGripper_GamePieceDistanceThreshold"); + /* * Stacker */ diff --git a/sysProps.xml b/sysProps.xml index 07383f8a413502b8a10e302d25425cd3f19a6536..b3bc9559a0a88a9389d09c60efd53cc47e1c3d18 100644 GIT binary patch delta 34 ncmdm|w@+`w0YP3v1|tRw20aD?5S;AKVLdrPm}N7MkP#~YpfU&d delta 34 ncmdm|w@+`w0YP4422%zz20aD?5S;AKVLdrPm}N7MkP#~Ypn?bb From ba1b207997c7d995ab9e3540bc7c105a0c0aef15 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Mon, 16 Feb 2015 20:47:13 +0200 Subject: [PATCH 20/29] Prepared commands for state machine --- .../robot/stacker/StackerPosition.java | 2 +- .../stacker/commands/MoveStackerToFloor.java | 20 +--------- .../stacker/commands/MoveStackerToStep.java | 39 +------------------ .../stacker/commands/MoveStackerToTote.java | 26 ------------- .../team3316/robot/subsystems/Stacker.java | 10 +---- 5 files changed, 4 insertions(+), 93 deletions(-) diff --git a/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java b/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java index 4ae1df1..e7867c1 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/StackerPosition.java @@ -2,5 +2,5 @@ public enum StackerPosition { - Tote, Step, Floor, StuckOnContainer; + Tote, Step, Floor; } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java index 98bad13..f8527ec 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java @@ -10,27 +10,9 @@ */ public class MoveStackerToFloor extends MoveStacker { - protected void setSolenoids() { - if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.None) - { - Robot.stacker.openSolenoidGripper(); - } - Robot.stacker.closeSolenoidContainer(); - Robot.stacker.openSolenoidUpper(); Robot.stacker.openSolenoidBottom(); - } - - protected boolean isFinished () - { - if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) - { - return (Robot.stacker.getPosition() == StackerPosition.StuckOnContainer); - } - else - { - return (Robot.stacker.getPosition() == StackerPosition.Floor); - } + Robot.stacker.openSolenoidUpper(); } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java index e2ff146..14c268c 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java @@ -6,46 +6,9 @@ public class MoveStackerToStep extends MoveStacker { - protected void initialize() + protected void setSolenoids() { - /* - * If one of the ratchets is not in place and they should be pressed, dont start - */ - if ( Robot.stacker.getPosition() == StackerPosition.Floor && - (!Robot.stacker.getSwitchLeft() || !Robot.stacker.getSwitchRight())) - { - this.cancel(); - } - else - { - super.initialize(); - } - } - - protected void setSolenoids() - { - if(Robot.stacker.getPosition() == StackerPosition.Tote) - { - Robot.stacker.openSolenoidGripper(); - } - //TODO: check if the condition should be if the command started when the stacker was stuck on a container - if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) - { - Robot.stacker.openSolenoidContainer(); - } Robot.stacker.openSolenoidUpper(); Robot.stacker.closeSolenoidBottom(); } - - protected boolean isFinished () - { - if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) - { - return (Robot.stacker.getPosition() == StackerPosition.StuckOnContainer); - } - else - { - return (Robot.stacker.getPosition() == StackerPosition.Step); - } - } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java index a8ef7e6..de6c121 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java @@ -9,35 +9,9 @@ public class MoveStackerToTote extends MoveStacker { - protected void initialize() - { - /* - * If one of the ratchets is not in place and they should be pressed, dont start - */ - if ( Robot.stacker.getPosition() == StackerPosition.Floor && - (!Robot.stacker.getSwitchLeft() || !Robot.stacker.getSwitchRight())) - { - this.cancel(); - } - else - { - super.initialize(); - } - } - protected void setSolenoids() { - //TODO: check if the condition should be if the command started when the stacker was stuck on a container - if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container) - { - Robot.stacker.openSolenoidContainer(); - } Robot.stacker.closeSolenoidUpper(); Robot.stacker.closeSolenoidBottom(); } - - protected boolean isFinished () - { - return (Robot.stacker.getPosition() == StackerPosition.Tote); - } } diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java index c2ed692..a494985 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java @@ -34,8 +34,7 @@ public class Stacker extends Subsystem private double heightFloorMin, heightFloorMax, heightStepMin, heightStepMax, - heightToteMin, heightToteMax, - heightStuckOnContainerMin, heightStuckOnContainerMax; + heightToteMin, heightToteMax; private Stack stack; @@ -152,10 +151,6 @@ else if ((height > heightStepMin) && (height < heightStepMax)) { return StackerPosition.Step; } - else if ((height > heightStuckOnContainerMin) && (height < heightStuckOnContainerMax)) - { - return StackerPosition.StuckOnContainer; - } else { return null; @@ -174,9 +169,6 @@ private void updateHeights () heightStepMin = (double) config.get("stacker_HeightStepMinimum"); heightStepMax = (double) config.get("stacker_HeightStepMaximum"); - - heightStuckOnContainerMin = (double) config.get("stacker_HeightStuckOnContainerMinimum"); - heightStuckOnContainerMax = (double) config.get("stacker_HeightStuckOnContainerMaximum"); } catch (ConfigException e) { From 8815731d322fee772993b54716624e30726114d3 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Mon, 16 Feb 2015 23:30:54 +0200 Subject: [PATCH 21/29] Added stacker manager as a private class in stacker --- .../frc/team3316/robot/humanIO/SDB.java | 4 +- .../stacker/commands/AddGamePieceToStack.java | 40 ---- .../robot/stacker/commands/MoveStacker.java | 4 +- .../stacker/commands/MoveStackerToFloor.java | 7 +- .../stacker/commands/MoveStackerToStep.java | 7 +- .../stacker/commands/MoveStackerToTote.java | 7 +- .../team3316/robot/subsystems/Stacker.java | 218 ++++++++++++++---- 7 files changed, 198 insertions(+), 89 deletions(-) delete mode 100644 src/org/usfirst/frc/team3316/robot/stacker/commands/AddGamePieceToStack.java diff --git a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java index a478486..ef7ef2c 100644 --- a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java +++ b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java @@ -43,8 +43,8 @@ public void run () put ("Angular Velocity", Robot.chassis.getAngularVelocity()); put ("Angular Velocity Encoders", Robot.chassis.getAngularVelocityEncoders()); - put ("Left Ratchet", Robot.stacker.getSwitchLeft()); - put ("Right Ratchet", Robot.stacker.getSwitchRight()); + put ("Left Ratchet", Robot.stacker.getSwitchRatchetLeft()); + put ("Right Ratchet", Robot.stacker.getSwitchRatchetRight()); put ("Game Piece Switch", Robot.rollerGripper.getSwitchGamePiece()); diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/AddGamePieceToStack.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/AddGamePieceToStack.java deleted file mode 100644 index b640081..0000000 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/AddGamePieceToStack.java +++ /dev/null @@ -1,40 +0,0 @@ -package org.usfirst.frc.team3316.robot.stacker.commands; - -import org.usfirst.frc.team3316.robot.Robot; -import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; -import org.usfirst.frc.team3316.robot.stacker.GamePiece; -import org.usfirst.frc.team3316.robot.stacker.GamePieceType; - -import edu.wpi.first.wpilibj.command.Command; - -/** - * - */ -public class AddGamePieceToStack extends Command -{ - public AddGamePieceToStack() {} - - protected void initialize() - { - GamePieceCollected gpCollected = Robot.rollerGripper.getGamePieceCollected(); - if (gpCollected == GamePieceCollected.Container) - { - Robot.stacker.pushToStack(new GamePiece(GamePieceType.Container)); - } - else if (gpCollected == GamePieceCollected.Tote) - { - Robot.stacker.pushToStack(new GamePiece(GamePieceType.Tote)); - } - } - - protected void execute() {} - - protected boolean isFinished() - { - return true; - } - - protected void end() {} - - protected void interrupted() {} -} diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java index d62cca9..7a8e53f 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java @@ -22,7 +22,7 @@ public MoveStacker() protected void initialize() { - setSolenoids(); + set(); } protected void execute() {} @@ -36,5 +36,5 @@ protected void end() {} protected void interrupted() {} - protected abstract void setSolenoids(); + protected abstract void set(); } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java index f8527ec..e2a5711 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java @@ -10,9 +10,14 @@ */ public class MoveStackerToFloor extends MoveStacker { - protected void setSolenoids() + protected void set() { Robot.stacker.openSolenoidBottom(); Robot.stacker.openSolenoidUpper(); } + + protected boolean isFinished () + { + return (Robot.stacker.getPosition() == StackerPosition.Floor); + } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java index 14c268c..cc29455 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java @@ -6,9 +6,14 @@ public class MoveStackerToStep extends MoveStacker { - protected void setSolenoids() + protected void set() { Robot.stacker.openSolenoidUpper(); Robot.stacker.closeSolenoidBottom(); } + + protected boolean isFinished () + { + return (Robot.stacker.getPosition() == StackerPosition.Step); + } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java index de6c121..1bff8ca 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java @@ -9,9 +9,14 @@ public class MoveStackerToTote extends MoveStacker { - protected void setSolenoids() + protected void set() { Robot.stacker.closeSolenoidUpper(); Robot.stacker.closeSolenoidBottom(); } + + protected boolean isFinished () + { + return (Robot.stacker.getPosition() == StackerPosition.Tote); + } } diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java index a494985..044fe65 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java @@ -1,11 +1,13 @@ package org.usfirst.frc.team3316.robot.subsystems; import java.util.Stack; +import java.util.TimerTask; import org.usfirst.frc.team3316.robot.Robot; import org.usfirst.frc.team3316.robot.config.Config; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; import org.usfirst.frc.team3316.robot.logger.DBugLogger; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.stacker.GamePiece; import org.usfirst.frc.team3316.robot.stacker.GamePieceType; import org.usfirst.frc.team3316.robot.stacker.StackerPosition; @@ -20,6 +22,119 @@ */ public class Stacker extends Subsystem { + private class StackerManager extends TimerTask + { + + private StackerPosition currentState; + private StackerPosition setpointState; + + public StackerManager () + { + currentState = Robot.stacker.getPosition(); + setpointState = null; + + stack = new Stack (); + } + + public StackerPosition getCurrentState () + { + return currentState; + } + + public boolean setSetpointState (StackerPosition setpoint) + { + if (setpointState != null) + { + return false; + } + setpointState = setpoint; + return true; + } + + public void run () + { + currentState = Robot.stacker.getPosition(); + + if (setpointState == null) + { + return; + } + else if (currentState == setpointState) + { + setpointState = null; + return; + } + + GamePieceCollected gp = Robot.rollerGripper.getGamePieceCollected(); + + if (setpointState == StackerPosition.Tote) + { + if (currentState == StackerPosition.Step) + { + moveToTote(); + } + + else if (currentState == StackerPosition.Floor) + { + //TODO: check if following condition should include tote as well + if (gp == GamePieceCollected.Container) + { + openSolenoidContainer(); + openSolenoidGripper(); + } + moveToTote(); + } + } + + else if (setpointState == StackerPosition.Step) + { + if (currentState == StackerPosition.Tote) + { + if (gp == GamePieceCollected.None) //TODO: check if needs to open for container too + { + openSolenoidGripper(); + } + moveToStep(); + } + + else if (currentState == StackerPosition.Floor) + { + if (gp == GamePieceCollected.Container) + { + openSolenoidContainer(); + openSolenoidGripper(); + } + moveToStep(); + } + } + + else if (setpointState == StackerPosition.Floor) + { + if (currentState == StackerPosition.Tote) + { + if (gp == GamePieceCollected.None) + { + closeSolenoidContainer(); + openSolenoidGripper(); + } + moveToFloor(); + } + + else if (currentState == StackerPosition.Step) + { + if (gp == GamePieceCollected.None) + { + closeSolenoidContainer(); + openSolenoidGripper(); + } + moveToFloor(); + } + } + + }//end of run + + }//end of class + Config config = Robot.config; DBugLogger logger = Robot.logger; @@ -36,7 +151,9 @@ public class Stacker extends Subsystem heightStepMin, heightStepMax, heightToteMin, heightToteMax; - private Stack stack; + private Stack stack; + + private StackerManager manager; public Stacker () { @@ -57,18 +174,14 @@ public Stacker () switchRight = Robot.sensors.switchRatchetRight; switchLeft = Robot.sensors.switchRatchetLeft; - stack = new Stack (); + manager = new StackerManager(); + Robot.timer.schedule(manager, 0, 20); } public void initDefaultCommand() {} public boolean openSolenoidUpper () { - /* - * Upper solenoid is opened only when trying to move to floor - * Therefore it is the solenoid that when opened can harm the gripper or the container pistons - */ - solenoidContainer.set(DoubleSolenoid.Value.kReverse); solenoidUpper.set(DoubleSolenoid.Value.kForward); return true; } @@ -120,19 +233,16 @@ public double getHeight () return (1 / heightIR.getVoltage()); } - public boolean getSwitchRight () + public boolean getSwitchRatchetRight () { return switchRight.get(); } - public boolean getSwitchLeft () + public boolean getSwitchRatchetLeft () { return switchLeft.get(); } - /* - * TODO: check if StuckOnContainer is necessary (if it's not simply step or floor) - */ public StackerPosition getPosition () { updateHeights(); @@ -157,36 +267,7 @@ else if ((height > heightStepMin) && (height < heightStepMax)) } } - private void updateHeights () - { - try - { - heightFloorMin = (double) config.get("stacker_HeightFloorMinimum"); - heightFloorMax = (double) config.get("stacker_HeightFloorMaximum"); - - heightToteMin = (double) config.get("stacker_HeightToteMinimum"); - heightToteMax = (double) config.get("stacker_HeightToteMaximum"); - - heightStepMin = (double) config.get("stacker_HeightStepMinimum"); - heightStepMax = (double) config.get("stacker_HeightStepMaximum"); - } - catch (ConfigException e) - { - logger.severe(e); - } - } - - public DoubleSolenoid.Value getSolenoidContainer () - { - return solenoidContainer.get(); - } - - public DoubleSolenoid.Value getSolenoidGripper () - { - return solenoidGripper.get(); - } - - /* + /* * Stack methods */ public GamePiece getStackBase () @@ -217,5 +298,58 @@ public void clearStack () { stack.clear(); } + + private void addGamePiece () + { + GamePieceCollected gp = Robot.rollerGripper.getGamePieceCollected(); + if (gp == GamePieceCollected.Container) + { + Robot.stacker.pushToStack(new GamePiece(GamePieceType.Container)); + } + else if (gp == GamePieceCollected.Tote) + { + Robot.stacker.pushToStack(new GamePiece(GamePieceType.Tote)); + } + } + + private void updateHeights () + { + try + { + heightFloorMin = (double) config.get("stacker_HeightFloorMinimum"); + heightFloorMax = (double) config.get("stacker_HeightFloorMaximum"); + + heightToteMin = (double) config.get("stacker_HeightToteMinimum"); + heightToteMax = (double) config.get("stacker_HeightToteMaximum"); + + heightStepMin = (double) config.get("stacker_HeightStepMinimum"); + heightStepMax = (double) config.get("stacker_HeightStepMaximum"); + } + catch (ConfigException e) + { + logger.severe(e); + } + } + + /* + * Methods for StackerManager + */ + private void moveToFloor () + { + Robot.stacker.openSolenoidBottom(); + Robot.stacker.openSolenoidUpper(); + } + + private void moveToStep () + { + Robot.stacker.openSolenoidBottom(); + Robot.stacker.closeSolenoidUpper(); + } + + private void moveToTote () + { + Robot.stacker.closeSolenoidBottom(); + Robot.stacker.closeSolenoidUpper(); + } } From d422b22c15af8abb7e00764473398e3e3f2f9a10 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Tue, 17 Feb 2015 01:23:01 +0200 Subject: [PATCH 22/29] Added conditions to manager and fixed commands to work with manager --- src/org/usfirst/frc/team3316/robot/Robot.java | 1 + .../frc/team3316/robot/humanIO/SDB.java | 3 +- .../rollerGripper/GamePieceCollected.java | 12 +- .../robot/stacker/commands/MoveStacker.java | 34 ++++- .../stacker/commands/MoveStackerToFloor.java | 13 +- .../stacker/commands/MoveStackerToStep.java | 12 +- .../stacker/commands/MoveStackerToTote.java | 15 +- .../robot/subsystems/RollerGripper.java | 14 +- .../team3316/robot/subsystems/Stacker.java | 139 +++++++++++++----- 9 files changed, 158 insertions(+), 85 deletions(-) diff --git a/src/org/usfirst/frc/team3316/robot/Robot.java b/src/org/usfirst/frc/team3316/robot/Robot.java index 9ac69ab..bdf0543 100644 --- a/src/org/usfirst/frc/team3316/robot/Robot.java +++ b/src/org/usfirst/frc/team3316/robot/Robot.java @@ -92,6 +92,7 @@ public void robotInit() */ timer = new Timer(); chassis.timerInit(); + stacker.timerInit(); sdb.timerInit(); } diff --git a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java index ef7ef2c..14e855e 100644 --- a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java +++ b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java @@ -196,7 +196,8 @@ private void initSDB () putConfigVariableInSDB("rollerGripper_ContainerDistanceMinimum"); putConfigVariableInSDB("rollerGripper_ContainerDistanceMaximum"); - putConfigVariableInSDB("rollerGripper_GamePieceDistanceThreshold"); + putConfigVariableInSDB("rollerGripper_SomethingDistanceThreshold"); + putConfigVariableInSDB("rollerGripper_UnsureDistanceThreshold"); /* * Stacker diff --git a/src/org/usfirst/frc/team3316/robot/rollerGripper/GamePieceCollected.java b/src/org/usfirst/frc/team3316/robot/rollerGripper/GamePieceCollected.java index cedfd51..10492f4 100644 --- a/src/org/usfirst/frc/team3316/robot/rollerGripper/GamePieceCollected.java +++ b/src/org/usfirst/frc/team3316/robot/rollerGripper/GamePieceCollected.java @@ -2,5 +2,15 @@ public enum GamePieceCollected { - Tote, Container, Unsure, None; + /* + * Ordered from closest to furthest: + + * Tote - a tote is in the gripper + * Container - a container is in the gripper + * Something - something is in the gripper, not sure what + * Unsure - unsure if there's something in the gripper + * None - the gripper is empty + */ + + Tote, Container, Something, Unsure, None; } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java index 7a8e53f..fdc4d6e 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java @@ -4,6 +4,7 @@ import org.usfirst.frc.team3316.robot.config.Config; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; import org.usfirst.frc.team3316.robot.logger.DBugLogger; +import org.usfirst.frc.team3316.robot.stacker.StackerPosition; import edu.wpi.first.wpilibj.command.Command; @@ -15,26 +16,45 @@ public abstract class MoveStacker extends Command DBugLogger logger = Robot.logger; Config config = Robot.config; + private StackerPosition setpoint; + + private boolean setSuccessful = false; + public MoveStacker() { requires(Robot.stacker); + setpoint = setSetpointState(); } - protected void initialize() + protected void initialize() {} + + protected void execute() { - set(); + if (!setSuccessful) + { + set(); + } } - protected void execute() {} - protected boolean isFinished() { - return true; + return (Robot.stacker.getPosition() == setpoint); } - protected void end() {} + protected void end() + { + setSuccessful = false; + } protected void interrupted() {} - protected abstract void set(); + private void set () + { + if (Robot.stacker.setSetpointState(setpoint) == setpoint) + { + setSuccessful = true; + } + } + + protected abstract StackerPosition setSetpointState(); } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java index e2a5711..58d814b 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToFloor.java @@ -1,8 +1,5 @@ package org.usfirst.frc.team3316.robot.stacker.commands; -import org.usfirst.frc.team3316.robot.Robot; -import org.usfirst.frc.team3316.robot.config.Config.ConfigException; -import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.stacker.StackerPosition; /** @@ -10,14 +7,8 @@ */ public class MoveStackerToFloor extends MoveStacker { - protected void set() + protected StackerPosition setSetpointState() { - Robot.stacker.openSolenoidBottom(); - Robot.stacker.openSolenoidUpper(); - } - - protected boolean isFinished () - { - return (Robot.stacker.getPosition() == StackerPosition.Floor); + return StackerPosition.Floor; } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java index cc29455..8291bb1 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToStep.java @@ -1,19 +1,11 @@ package org.usfirst.frc.team3316.robot.stacker.commands; -import org.usfirst.frc.team3316.robot.Robot; -import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; import org.usfirst.frc.team3316.robot.stacker.StackerPosition; public class MoveStackerToStep extends MoveStacker { - protected void set() + protected StackerPosition setSetpointState() { - Robot.stacker.openSolenoidUpper(); - Robot.stacker.closeSolenoidBottom(); - } - - protected boolean isFinished () - { - return (Robot.stacker.getPosition() == StackerPosition.Step); + return StackerPosition.Step; } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java index 1bff8ca..34700a2 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStackerToTote.java @@ -1,22 +1,11 @@ package org.usfirst.frc.team3316.robot.stacker.commands; -import org.usfirst.frc.team3316.robot.Robot; -import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; -import org.usfirst.frc.team3316.robot.stacker.GamePieceType; import org.usfirst.frc.team3316.robot.stacker.StackerPosition; -import edu.wpi.first.wpilibj.DoubleSolenoid; - public class MoveStackerToTote extends MoveStacker { - protected void set() - { - Robot.stacker.closeSolenoidUpper(); - Robot.stacker.closeSolenoidBottom(); - } - - protected boolean isFinished () + protected StackerPosition setSetpointState() { - return (Robot.stacker.getPosition() == StackerPosition.Tote); + return StackerPosition.Tote; } } diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java b/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java index 13666ea..35920d1 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java @@ -36,7 +36,10 @@ public class RollerGripper extends Subsystem toteDistanceMax, containerDistanceMin, containerDistanceMax, - gpDistanceThreshold; + somethingDistanceThreshold, + unsureDistanceThreshold; + + private boolean newGamePiece = false; private Roll defaultRoll; @@ -104,7 +107,11 @@ else if (gpDistance > containerDistanceMin && gpDistance < containerDistanceMax) } else { - if (gpDistance < gpDistanceThreshold) + if (gpDistance < somethingDistanceThreshold) + { + return GamePieceCollected.Something; + } + else if (gpDistance < unsureDistanceThreshold) { return GamePieceCollected.Unsure; } @@ -125,7 +132,8 @@ private void updateDistanceVariables () containerDistanceMin = (double) config.get("rollerGripper_ContainerDistanceMinimum"); containerDistanceMax = (double) config.get("rollerGripper_ContainerDistanceMaximum"); - gpDistanceThreshold = (double) config.get("rollerGripper_GamePieceDistanceThreshold"); + somethingDistanceThreshold = (double) config.get("rollerGripper_SomethingDistanceThreshold"); + unsureDistanceThreshold = (double) config.get("rollerGripper_UnsureDistanceThreshold"); } catch (ConfigException e) { diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java index 044fe65..4160921 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java @@ -28,6 +28,8 @@ private class StackerManager extends TimerTask private StackerPosition currentState; private StackerPosition setpointState; + private int directLoweringMaxSize; + public StackerManager () { currentState = Robot.stacker.getPosition(); @@ -36,38 +38,22 @@ public StackerManager () stack = new Stack (); } - public StackerPosition getCurrentState () + public StackerPosition setSetpointState (StackerPosition setpoint) { - return currentState; - } - - public boolean setSetpointState (StackerPosition setpoint) - { - if (setpointState != null) + + if (setpoint == null) { - return false; + return null; } - setpointState = setpoint; - return true; - } - - public void run () - { - currentState = Robot.stacker.getPosition(); - if (setpointState == null) - { - return; - } - else if (currentState == setpointState) + if (setpointState != null) { - setpointState = null; - return; + return null; } - + GamePieceCollected gp = Robot.rollerGripper.getGamePieceCollected(); - if (setpointState == StackerPosition.Tote) + if (setpoint == StackerPosition.Tote) { if (currentState == StackerPosition.Step) { @@ -76,7 +62,14 @@ else if (currentState == setpointState) else if (currentState == StackerPosition.Floor) { - //TODO: check if following condition should include tote as well + //if one of the ratchets is not in place - abort + if (!Robot.stacker.getSwitchRatchetLeft() || + !Robot.stacker.getSwitchRatchetRight()) + { + return null; + } + + //TODO: check if following condition should include tote as well (only for opening gripper) if (gp == GamePieceCollected.Container) { openSolenoidContainer(); @@ -86,7 +79,7 @@ else if (currentState == StackerPosition.Floor) } } - else if (setpointState == StackerPosition.Step) + else if (setpoint == StackerPosition.Step) { if (currentState == StackerPosition.Tote) { @@ -99,6 +92,14 @@ else if (setpointState == StackerPosition.Step) else if (currentState == StackerPosition.Floor) { + //if one of the ratchets is not in place - abort + if (!Robot.stacker.getSwitchRatchetLeft() || + !Robot.stacker.getSwitchRatchetRight()) + { + return null; + } + + //TODO: check if following condition should include tote as well (only for opening gripper) if (gp == GamePieceCollected.Container) { openSolenoidContainer(); @@ -108,16 +109,26 @@ else if (currentState == StackerPosition.Floor) } } - else if (setpointState == StackerPosition.Floor) + else if (setpoint == StackerPosition.Floor) { if (currentState == StackerPosition.Tote) - { + { if (gp == GamePieceCollected.None) { closeSolenoidContainer(); openSolenoidGripper(); } - moveToFloor(); + + //TODO: check what is the max size before lowering needs to be separated into two parts + if (stack.size() > directLoweringMaxSize) + { + setpointState = StackerPosition.Step; + moveToStep(); + } + else + { + moveToFloor(); + } } else if (currentState == StackerPosition.Step) @@ -130,8 +141,36 @@ else if (currentState == StackerPosition.Step) moveToFloor(); } } - - }//end of run + setpointState = setpoint; + + return setpointState; + } + + public void run () + { + currentState = Robot.stacker.getPosition(); + + if (currentState == setpointState) + { + setpointState = null; + return; + } + + updateNewGamePiece(); + updateVariables(); + } + + private void updateVariables () + { + try + { + directLoweringMaxSize = (int) config.get("stacker_StackerManager_DirectLoweringMaxSize"); + } + catch (ConfigException e) + { + logger.severe(e); + } + } }//end of class @@ -154,7 +193,9 @@ else if (currentState == StackerPosition.Step) private Stack stack; private StackerManager manager; - + + private boolean newGamePiece = false; + public Stacker () { /* In order to get to each height we use: @@ -173,32 +214,35 @@ public Stacker () switchRight = Robot.sensors.switchRatchetRight; switchLeft = Robot.sensors.switchRatchetLeft; - + } + + public void timerInit () + { manager = new StackerManager(); Robot.timer.schedule(manager, 0, 20); } public void initDefaultCommand() {} - public boolean openSolenoidUpper () + private boolean openSolenoidUpper () { solenoidUpper.set(DoubleSolenoid.Value.kForward); return true; } - public boolean closeSolenoidUpper () + private boolean closeSolenoidUpper () { solenoidUpper.set(DoubleSolenoid.Value.kReverse); return true; } - public boolean openSolenoidBottom () + private boolean openSolenoidBottom () { solenoidBottom.set(DoubleSolenoid.Value.kForward); return true; } - public boolean closeSolenoidBottom () + private boolean closeSolenoidBottom () { solenoidBottom.set(DoubleSolenoid.Value.kReverse); return true; @@ -216,7 +260,7 @@ public boolean closeSolenoidContainer () return true; } - public boolean openSolenoidGripper () + public boolean openSolenoidGripper () { solenoidGripper.set(DoubleSolenoid.Value.kForward); return true; @@ -332,8 +376,13 @@ private void updateHeights () } /* - * Methods for StackerManager + * StackerManager Methods */ + public StackerPosition setSetpointState (StackerPosition setpoint) + { + return manager.setSetpointState(setpoint); + } + private void moveToFloor () { Robot.stacker.openSolenoidBottom(); @@ -351,5 +400,17 @@ private void moveToTote () Robot.stacker.closeSolenoidBottom(); Robot.stacker.closeSolenoidUpper(); } + + private void updateNewGamePiece () + { + if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Unsure) + { + newGamePiece = true; + } + else if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.None) + { + newGamePiece = false; + } + } } From 1786d4b6dab21cec3b6c59036571a4046bf9e7a4 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Tue, 17 Feb 2015 02:35:40 +0200 Subject: [PATCH 23/29] Deleted sequences for testing --- .../robot/sequences/AddGamePieceSequence.java | 20 ---------- .../robot/sequences/PickupSequence.java | 37 ----------------- .../robot/sequences/StepAutonSequence.java | 40 ------------------- 3 files changed, 97 deletions(-) delete mode 100644 src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java delete mode 100644 src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java delete mode 100644 src/org/usfirst/frc/team3316/robot/sequences/StepAutonSequence.java diff --git a/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java deleted file mode 100644 index 2b6fb26..0000000 --- a/src/org/usfirst/frc/team3316/robot/sequences/AddGamePieceSequence.java +++ /dev/null @@ -1,20 +0,0 @@ -package org.usfirst.frc.team3316.robot.sequences; - -import org.usfirst.frc.team3316.robot.stacker.commands.AddGamePieceToStack; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToFloor; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToTote; - -import edu.wpi.first.wpilibj.command.CommandGroup; - -/** - * - */ -public class AddGamePieceSequence extends CommandGroup -{ - public AddGamePieceSequence() - { - addSequential(new AddGamePieceToStack()); - addSequential(new MoveStackerToFloor()); - addSequential(new MoveStackerToTote()); - } -} diff --git a/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java deleted file mode 100644 index a7ac25c..0000000 --- a/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java +++ /dev/null @@ -1,37 +0,0 @@ -package org.usfirst.frc.team3316.robot.sequences; - -import org.usfirst.frc.team3316.robot.Robot; -import org.usfirst.frc.team3316.robot.config.Config; -import org.usfirst.frc.team3316.robot.logger.DBugLogger; -import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollIn; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToFloor; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToTote; - -import edu.wpi.first.wpilibj.command.CommandGroup; - -/** - * - */ -public class PickupSequence extends CommandGroup -{ - DBugLogger logger = Robot.logger; - Config config = Robot.config; - - AddGamePieceSequence addGamePieceSequence; - - public PickupSequence () - { - addSequential(new MoveStackerToTote()); //TODO: check if this doesn't cause bugs - addSequential(new RollIn()); - - addGamePieceSequence = new AddGamePieceSequence(); - } - - protected void end () - { - if (!Robot.stacker.isFull() && Robot.rollerGripper.getSwitchGamePiece()) - { - addGamePieceSequence.start(); - } - } -} diff --git a/src/org/usfirst/frc/team3316/robot/sequences/StepAutonSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/StepAutonSequence.java deleted file mode 100644 index 383fe83..0000000 --- a/src/org/usfirst/frc/team3316/robot/sequences/StepAutonSequence.java +++ /dev/null @@ -1,40 +0,0 @@ -package org.usfirst.frc.team3316.robot.sequences; - -import org.usfirst.frc.team3316.robot.Robot; -import org.usfirst.frc.team3316.robot.anschluss.commands.OpenAnschluss; -import org.usfirst.frc.team3316.robot.chassis.commands.RobotOrientedNavigation; -import org.usfirst.frc.team3316.robot.config.Config; -import org.usfirst.frc.team3316.robot.config.Config.ConfigException; -import org.usfirst.frc.team3316.robot.logger.DBugLogger; - -import edu.wpi.first.wpilibj.command.CommandGroup; - -/** - * - */ -public class StepAutonSequence extends CommandGroup { - - DBugLogger logger = Robot.logger; - Config config = Robot.config; - - private double distanceForward; - - public StepAutonSequence() { - setStepAutonSequenceDistanceStraight(); - - addSequential(new OpenAnschluss()); - addSequential(new RobotOrientedNavigation(0, distanceForward, 0)); - } - - private void setStepAutonSequenceDistanceStraight () - { - try - { - distanceForward = (double)config.get("chassis_StepAutonSequence_DistanceForward"); - } - catch (ConfigException e) - { - logger.severe(e); - } - } -} From 9275a03fa721ee1111a48da3eb6c67ab8942b7cb Mon Sep 17 00:00:00 2001 From: frc3316 Date: Tue, 17 Feb 2015 03:42:39 +0200 Subject: [PATCH 24/29] Deleted separate roller gripper commands and removed stack tracking --- .../robot/rollerGripper/commands/RollIn.java | 25 ----- .../robot/rollerGripper/commands/RollOut.java | 26 ----- .../commands/RollTurnClockwise.java | 19 ---- .../commands/RollTurnCounterClockwise.java | 19 ---- .../commands/WaitForGamePiece.java | 28 ++++++ .../robot/sequences/PickupSequence.java | 36 +++++++ .../robot/subsystems/RollerGripper.java | 7 +- .../team3316/robot/subsystems/Stacker.java | 98 ++----------------- 8 files changed, 75 insertions(+), 183 deletions(-) delete mode 100644 src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollIn.java delete mode 100644 src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java delete mode 100644 src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollTurnClockwise.java delete mode 100644 src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollTurnCounterClockwise.java create mode 100644 src/org/usfirst/frc/team3316/robot/rollerGripper/commands/WaitForGamePiece.java create mode 100644 src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java diff --git a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollIn.java b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollIn.java deleted file mode 100644 index 351456b..0000000 --- a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollIn.java +++ /dev/null @@ -1,25 +0,0 @@ -package org.usfirst.frc.team3316.robot.rollerGripper.commands; - -import org.usfirst.frc.team3316.robot.Robot; -import org.usfirst.frc.team3316.robot.config.Config.ConfigException; - -public class RollIn extends Roll -{ - protected void setSpeeds() - { - try - { - this.left = (double) config.get("rollerGripper_RollIn_SpeedLeft"); - this.right = (double) config.get("rollerGripper_RollIn_SpeedRight"); - } - catch (ConfigException e) - { - logger.severe(e); - } - } - - protected boolean isFinished () - { - return Robot.rollerGripper.getSwitchGamePiece(); - } -} diff --git a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java deleted file mode 100644 index d63ec41..0000000 --- a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollOut.java +++ /dev/null @@ -1,26 +0,0 @@ -package org.usfirst.frc.team3316.robot.rollerGripper.commands; - -import org.usfirst.frc.team3316.robot.Robot; -import org.usfirst.frc.team3316.robot.config.Config.ConfigException; -import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; - -public class RollOut extends Roll -{ - protected void setSpeeds () - { - try - { - this.left = (double) config.get("rollerGripper_RollOut_SpeedLeft"); - this.right = (double) config.get("rollerGripper_RollOut_SpeedRight"); - } - catch (ConfigException e) - { - logger.severe(e); - } - } - - protected boolean isFinished () - { - return Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.None; - } -} diff --git a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollTurnClockwise.java b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollTurnClockwise.java deleted file mode 100644 index f8fcf92..0000000 --- a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollTurnClockwise.java +++ /dev/null @@ -1,19 +0,0 @@ -package org.usfirst.frc.team3316.robot.rollerGripper.commands; - -import org.usfirst.frc.team3316.robot.config.Config.ConfigException; - -public class RollTurnClockwise extends Roll -{ - protected void setSpeeds () - { - try - { - this.left = (double) config.get("rollerGripper_RollTurnClockwise_SpeedLeft"); - this.right = (double) config.get("rollerGripper_RollTurnClockwise_SpeedRight"); - } - catch (ConfigException e) - { - logger.severe(e); - } - } -} diff --git a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollTurnCounterClockwise.java b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollTurnCounterClockwise.java deleted file mode 100644 index 30afb2a..0000000 --- a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/RollTurnCounterClockwise.java +++ /dev/null @@ -1,19 +0,0 @@ -package org.usfirst.frc.team3316.robot.rollerGripper.commands; - -import org.usfirst.frc.team3316.robot.config.Config.ConfigException; - -public class RollTurnCounterClockwise extends Roll -{ - protected void setSpeeds () - { - try - { - this.left = (double) config.get("rollerGripper_RollTurnCounterClockwise_SpeedLeft"); - this.right = (double) config.get("rollerGripper_RollTurnCounterClockwise_SpeedRight"); - } - catch (ConfigException e) - { - logger.severe(e); - } - } -} diff --git a/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/WaitForGamePiece.java b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/WaitForGamePiece.java new file mode 100644 index 0000000..c6f9099 --- /dev/null +++ b/src/org/usfirst/frc/team3316/robot/rollerGripper/commands/WaitForGamePiece.java @@ -0,0 +1,28 @@ +package org.usfirst.frc.team3316.robot.rollerGripper.commands; + +import org.usfirst.frc.team3316.robot.Robot; +import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; + +import edu.wpi.first.wpilibj.command.Command; + +/** + * Command that finishes when a game piece is completely collected + */ +public class WaitForGamePiece extends Command +{ + public WaitForGamePiece() {} + + protected void initialize() {} + + protected void execute() {} + + protected boolean isFinished() + { + return (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Container || + Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Tote); + } + + protected void end() {} + + protected void interrupted() {} +} diff --git a/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java b/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java new file mode 100644 index 0000000..e5c97c2 --- /dev/null +++ b/src/org/usfirst/frc/team3316/robot/sequences/PickupSequence.java @@ -0,0 +1,36 @@ +package org.usfirst.frc.team3316.robot.sequences; + +import org.usfirst.frc.team3316.robot.rollerGripper.commands.WaitForGamePiece; +import org.usfirst.frc.team3316.robot.stacker.commands.CloseGripper; +import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToFloor; +import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToTote; + +import edu.wpi.first.wpilibj.command.Command; +import edu.wpi.first.wpilibj.command.CommandGroup; + +/** + * + */ +public class PickupSequence extends CommandGroup +{ + Command moveToEndPosition; + + public PickupSequence() + { + addSequential(new MoveStackerToTote()); + addSequential(new CloseGripper()); + addSequential(new WaitForGamePiece()); + + //TODO: check if this should be changed to a sequence of floor --> step + moveToEndPosition = new MoveStackerToFloor(); + } + + protected void end () + { + /* + * This is in end because we don't want this to execute if the sequence + * was cancelled (and interrupted was called instead of end) + */ + moveToEndPosition.start(); + } +} diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java b/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java index 35920d1..83d306d 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/RollerGripper.java @@ -30,8 +30,7 @@ public class RollerGripper extends Subsystem private double leftScale, rightScale; - // Variables for getGamePieceCollected() - // They are set in updateDistanceVariables() + // Variables for getGamePieceCollected(). They are set in updateDistanceVariables(). private double toteDistanceMin, toteDistanceMax, containerDistanceMin, @@ -39,8 +38,6 @@ public class RollerGripper extends Subsystem somethingDistanceThreshold, unsureDistanceThreshold; - private boolean newGamePiece = false; - private Roll defaultRoll; public RollerGripper () @@ -102,7 +99,7 @@ else if (gpDistance > containerDistanceMin && gpDistance < containerDistanceMax) } else { - return GamePieceCollected.Unsure; + return GamePieceCollected.Something; } } else diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java index 4160921..b9237e6 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java @@ -1,6 +1,5 @@ package org.usfirst.frc.team3316.robot.subsystems; -import java.util.Stack; import java.util.TimerTask; import org.usfirst.frc.team3316.robot.Robot; @@ -8,14 +7,13 @@ import org.usfirst.frc.team3316.robot.config.Config.ConfigException; import org.usfirst.frc.team3316.robot.logger.DBugLogger; import org.usfirst.frc.team3316.robot.rollerGripper.GamePieceCollected; -import org.usfirst.frc.team3316.robot.stacker.GamePiece; -import org.usfirst.frc.team3316.robot.stacker.GamePieceType; import org.usfirst.frc.team3316.robot.stacker.StackerPosition; import edu.wpi.first.wpilibj.AnalogInput; import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.DoubleSolenoid; import edu.wpi.first.wpilibj.command.Subsystem; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; /** * @@ -28,14 +26,10 @@ private class StackerManager extends TimerTask private StackerPosition currentState; private StackerPosition setpointState; - private int directLoweringMaxSize; - public StackerManager () { currentState = Robot.stacker.getPosition(); setpointState = null; - - stack = new Stack (); } public StackerPosition setSetpointState (StackerPosition setpoint) @@ -86,6 +80,7 @@ else if (setpoint == StackerPosition.Step) if (gp == GamePieceCollected.None) //TODO: check if needs to open for container too { openSolenoidGripper(); + closeSolenoidContainer(); } moveToStep(); } @@ -113,18 +108,15 @@ else if (setpoint == StackerPosition.Floor) { if (currentState == StackerPosition.Tote) { - if (gp == GamePieceCollected.None) + if (gp == GamePieceCollected.None || + gp == GamePieceCollected.Unsure) { closeSolenoidContainer(); openSolenoidGripper(); - } - - //TODO: check what is the max size before lowering needs to be separated into two parts - if (stack.size() > directLoweringMaxSize) - { setpointState = StackerPosition.Step; moveToStep(); } + else { moveToFloor(); @@ -156,20 +148,9 @@ public void run () return; } - updateNewGamePiece(); - updateVariables(); - } - - private void updateVariables () - { - try - { - directLoweringMaxSize = (int) config.get("stacker_StackerManager_DirectLoweringMaxSize"); - } - catch (ConfigException e) - { - logger.severe(e); - } + //FOR TESTING. NEEDS TO BE REMOVED. + SmartDashboard.putString("Current State", currentState.toString()); + SmartDashboard.putString("Setpoint State", setpointState.toString()); } }//end of class @@ -190,12 +171,8 @@ private void updateVariables () heightStepMin, heightStepMax, heightToteMin, heightToteMax; - private Stack stack; - private StackerManager manager; - private boolean newGamePiece = false; - public Stacker () { /* In order to get to each height we use: @@ -224,7 +201,7 @@ public void timerInit () public void initDefaultCommand() {} - private boolean openSolenoidUpper () + private boolean openSolenoidUpper () { solenoidUpper.set(DoubleSolenoid.Value.kForward); return true; @@ -311,51 +288,6 @@ else if ((height > heightStepMin) && (height < heightStepMax)) } } - /* - * Stack methods - */ - public GamePiece getStackBase () - { - if (stack.isEmpty()) - { - return null; - } - return stack.get(0); - } - - public boolean isFull() - { - return stack.size() >= 6; - } - - public Stack getStack() - { - return stack; - } - - public void pushToStack(GamePiece g) - { - stack.push(g); - } - - public void clearStack () - { - stack.clear(); - } - - private void addGamePiece () - { - GamePieceCollected gp = Robot.rollerGripper.getGamePieceCollected(); - if (gp == GamePieceCollected.Container) - { - Robot.stacker.pushToStack(new GamePiece(GamePieceType.Container)); - } - else if (gp == GamePieceCollected.Tote) - { - Robot.stacker.pushToStack(new GamePiece(GamePieceType.Tote)); - } - } - private void updateHeights () { try @@ -400,17 +332,5 @@ private void moveToTote () Robot.stacker.closeSolenoidBottom(); Robot.stacker.closeSolenoidUpper(); } - - private void updateNewGamePiece () - { - if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.Unsure) - { - newGamePiece = true; - } - else if (Robot.rollerGripper.getGamePieceCollected() == GamePieceCollected.None) - { - newGamePiece = false; - } - } } From 1e4f0eb1a0b5d42fb758cfc2d6de437362e770cf Mon Sep 17 00:00:00 2001 From: frc3316 Date: Tue, 17 Feb 2015 03:53:51 +0200 Subject: [PATCH 25/29] Changed buttons for pickup sequence --- .../frc/team3316/robot/humanIO/Joysticks.java | 30 +++---------------- 1 file changed, 4 insertions(+), 26 deletions(-) diff --git a/src/org/usfirst/frc/team3316/robot/humanIO/Joysticks.java b/src/org/usfirst/frc/team3316/robot/humanIO/Joysticks.java index 1dde7ce..1b52f60 100644 --- a/src/org/usfirst/frc/team3316/robot/humanIO/Joysticks.java +++ b/src/org/usfirst/frc/team3316/robot/humanIO/Joysticks.java @@ -9,15 +9,11 @@ import org.usfirst.frc.team3316.robot.config.Config; import org.usfirst.frc.team3316.robot.config.Config.ConfigException; import org.usfirst.frc.team3316.robot.logger.DBugLogger; -import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollIn; -import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollOut; -import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollTurnClockwise; -import org.usfirst.frc.team3316.robot.rollerGripper.commands.RollTurnCounterClockwise; +import org.usfirst.frc.team3316.robot.sequences.PickupSequence; import org.usfirst.frc.team3316.robot.stacker.commands.CloseGripper; import org.usfirst.frc.team3316.robot.stacker.commands.HoldContainer; import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToFloor; import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToStep; -import org.usfirst.frc.team3316.robot.stacker.commands.MoveStackerToTote; import org.usfirst.frc.team3316.robot.stacker.commands.OpenGripper; import org.usfirst.frc.team3316.robot.stacker.commands.ReleaseContainer; @@ -70,7 +66,7 @@ public boolean get() public JoystickButton moveStackerToFloor, moveStackerToStep, - moveStackerToTote; + pickup; //pickup replaces moveStackerToTote public JoystickButton holdContainer, releaseContainer; @@ -105,24 +101,6 @@ public void initButtons () */ try { - /* - * Roller Gripper - */ - buttonRollIn = new POVButton(joystickOperator, - (int) config.get("BUTTON_ROLL_IN")); - buttonRollIn.whileHeld(new RollIn()); - - buttonRollOut = new POVButton(joystickOperator, - (int) config.get("BUTTON_ROLL_OUT")); - buttonRollOut.whileHeld(new RollOut()); - - buttonRollTurnClockwise = new POVButton(joystickOperator, - (int) config.get("BUTTON_ROLL_TURN_CLOCKWISE")); - buttonRollTurnClockwise.whileHeld(new RollTurnClockwise()); - - buttonRollTurnCounterClockwise = new POVButton(joystickOperator, - (int) config.get("BUTTON_ROLL_TURN_COUNTER_CLOCKWISE")); - buttonRollTurnCounterClockwise.whileHeld(new RollTurnCounterClockwise()); /* * Stacker @@ -135,9 +113,9 @@ public void initButtons () (int) config.get("BUTTON_MOVE_STACKER_TO_STEP")); moveStackerToStep.whenPressed(new MoveStackerToStep()); - moveStackerToTote = new JoystickButton(joystickOperator, + pickup = new JoystickButton(joystickOperator, (int) config.get("BUTTON_MOVE_STACKER_TO_TOTE")); - moveStackerToTote.whenPressed(new MoveStackerToTote()); + pickup.whenPressed(new PickupSequence()); holdContainer = new JoystickButton(joystickOperator, (int) config.get("BUTTON_HOLD_CONTAINER")); From 3908a58301100faed11156000daaa617be736a63 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Tue, 17 Feb 2015 04:37:16 +0200 Subject: [PATCH 26/29] Removed second center motor controller --- src/org/usfirst/frc/team3316/robot/robotIO/Actuators.java | 8 +++----- .../usfirst/frc/team3316/robot/subsystems/Chassis.java | 8 +++----- 2 files changed, 6 insertions(+), 10 deletions(-) diff --git a/src/org/usfirst/frc/team3316/robot/robotIO/Actuators.java b/src/org/usfirst/frc/team3316/robot/robotIO/Actuators.java index 89602b8..1af8ff4 100644 --- a/src/org/usfirst/frc/team3316/robot/robotIO/Actuators.java +++ b/src/org/usfirst/frc/team3316/robot/robotIO/Actuators.java @@ -23,7 +23,7 @@ public class Actuators */ public SpeedController chassisMotorControllerLeft1, chassisMotorControllerLeft2; public SpeedController chassisMotorControllerRight1, chassisMotorControllerRight2; - public SpeedController chassisMotorControllerCenter1, chassisMotorControllerCenter2; + public SpeedController chassisMotorControllerCenter; /* * Stacker @@ -61,8 +61,7 @@ public Actuators () chassisMotorControllerRight1 = new VictorSP ((int) config.get("CHASSIS_MOTOR_CONTROLLER_RIGHT_1")); chassisMotorControllerRight2 = new VictorSP ((int) config.get("CHASSIS_MOTOR_CONTROLLER_RIGHT_2")); - chassisMotorControllerCenter1 = new VictorSP((int) config.get("CHASSIS_MOTOR_CONTROLLER_CENTER_1")); - chassisMotorControllerCenter2 = new VictorSP((int) config.get("CHASSIS_MOTOR_CONTROLLER_CENTER_2")); + chassisMotorControllerCenter = new VictorSP((int) config.get("CHASSIS_MOTOR_CONTROLLER_CENTER")); /* * Anschluss */ @@ -82,8 +81,7 @@ public Actuators () chassisMotorControllerRight1 = new Talon ((int) config.get("CHASSIS_MOTOR_CONTROLLER_RIGHT_1")); chassisMotorControllerRight2 = new Talon ((int) config.get("CHASSIS_MOTOR_CONTROLLER_RIGHT_2")); - chassisMotorControllerCenter1 = new Talon((int) config.get("CHASSIS_MOTOR_CONTROLLER_CENTER_1")); - chassisMotorControllerCenter2 = new Talon((int) config.get("CHASSIS_MOTOR_CONTROLLER_CENTER_2")); + chassisMotorControllerCenter = new Talon((int) config.get("CHASSIS_MOTOR_CONTROLLER_CENTER")); /* * Anschluss */ diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/Chassis.java b/src/org/usfirst/frc/team3316/robot/subsystems/Chassis.java index 5edf4c7..2cc5e1f 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/Chassis.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/Chassis.java @@ -183,7 +183,7 @@ public boolean removeIntegrator (NavigationIntegrator integrator) private SpeedController left1, left2; private SpeedController right1, right2; - private SpeedController center1, center2; + private SpeedController center; private IMUAdvanced navx; @@ -209,8 +209,7 @@ public Chassis () right1 = Robot.actuators.chassisMotorControllerRight1; right2 = Robot.actuators.chassisMotorControllerRight2; - center1 = Robot.actuators.chassisMotorControllerCenter1; - center2 = Robot.actuators.chassisMotorControllerCenter2; + center = Robot.actuators.chassisMotorControllerCenter; navx = Robot.sensors.navx; @@ -250,8 +249,7 @@ public boolean set (double left, double right, double center) this.right1.set (right * rightScale); this.right2.set (right * rightScale); - this.center1.set (center * centerScale); - this.center2.set (center * centerScale); + this.center.set (center * centerScale); return true; } From adc495f11e39f6838aa6ab569df711b66b766125 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Tue, 17 Feb 2015 08:00:36 +0200 Subject: [PATCH 27/29] Added current and setpoint states to SDB, set to null resets the setpoint --- dist/FRCUserProgram.jar | Bin 1785739 -> 1780392 bytes src/org/usfirst/frc/team3316/robot/Robot.java | 5 +-- .../frc/team3316/robot/humanIO/SDB.java | 2 ++ .../team3316/robot/subsystems/Stacker.java | 34 +++++++++++++----- sysProps.xml | Bin 5950 -> 5950 bytes 5 files changed, 31 insertions(+), 10 deletions(-) diff --git a/dist/FRCUserProgram.jar b/dist/FRCUserProgram.jar index 71fbe8fce66b9688db8bd6db1dcad4cedfd52b41..a516a349bfde0d2227b16996750fda0459769a6b 100644 GIT binary patch delta 41357 zcma&Mb97x%_bwdUwrw>=W7}+O+b2nb#m8wqpdEKW@``O;8vwgNy8r%qfZ{zPP zGaL*C1OyKkZ?C}uuu;bqMe|K+vPq%`4^y+c2w%KaTLCH5C{@)fP%_E|%dL1csnd+} zH|E&L1ead;Nm%}lH^OBR%{4^04Y*-+Z)Zh~!`n^?MC5teTzOgNd79*{dwJ>tyn}Dk z=wUTSsN!2eXjS9%F6uAw5ZJr9TPl%~MK1-k$I ze)fayei`|RPvA&=r#yRXMNdi?ur4dQ=$fT@MhDe0T}#(uz%|-K!y{*LZ0~KCS@PbUS};X_AfZ4E#&T9XXPaYCPN2l4<;1GU&7dmOcmP?c5yv? z=sPW;#)abSi6{(wKm8yC-8D%5^)u*YG+2nnJ7 zrGDZ!wR&GD=iNGwBEty;tt*Q(Ylp*DOKJ4E_*ez(I>szwKK z@)r_!gI%ZbISn|)d*MFw zIXvbY=wr@ELVp|z{sA)_ifH#V*>S_lQu1VKfQcavD@9{JGM42l11ocA^bgt>1~t^Z zW=lidJMK=_8#o?{EThf-r)R;TXdDLiUJOT`*SXs6jqXG1G5R(anDb6*@QkSHNJ@$;Ny)A=v2Bu!k(9<-6MBMQAS!8H zgGb^!-r`~G#}$Cu?n%et?4n-_?9*>{0O)cL-f8PGrqzUaEbzgP$?-_()%+BNC@oBZ zhop~5E<}Jg$nRqowYx`9eoJ`e`*BEfimqydx9j#=%x+R|k26G&Y|`)0tsKE{e(MFF z-K5=q)6JmU-DQ|WyXj$=#B?ZaeZ_X3b4P`E$cg^RFC7G@0BodDKtQhu>}H`e2mmeL zfxa{VMeMnO;&G42Ha}Ef{!-Xgp75?(cpvJxb-#4XXqc0x^{NI!eVU_c-Pgf&@q7aPB>+8Xws-tDxp2m5>qvm@ib9wVoKfA=_c zasCIsxx4-Y%br#LK$uVNKfvIZ^AF4fAVGiLXFpu;Uyo>1+CPmBJKH9a{znzt{V`Pn zpRXWsjEz{w5>xp3MT|3;y+ zMxg%oeDac03Kb7u3v07Ve<^o%(c1c8}0UmT1WV^OpO> z8|@AlSHL5@AMo>c!IHYAlEF=fdunrFxvssZJ7a?8rG9p|I@=Ux41Lq^6kkaZ&+MR9 zkdi38V1hY74c2pdyazyE)O*4m%B^F!m0SAL zfU0Z#jBlbKf)t_{Rg`1}`-TnOxq+{4au5v=0h9HzVJ`eMjRhsyxZ*j%)Wzsw-##Yq z_~p?zgWTU8gQl1Tyq#y?t_2kG4uPimLLb2dl6_LsoZGyoVcOLF{(~DE2Vh%KRi%8T zjx|z*!T9lpf1Fq<2C{U+#*$t~Bb+I=m}kI#Tx^)j{}Z!BO%->T){i?7yjJygGsX@u ztL3zY%Jc*ab2$hW+{WhrOHn+VvaQ5O4cac!5x3dTg&VYnIt%AlGMh4dGIddooBEFh zqNK9sB&Q2YTOlWbp63V>`a?*x3FSQ%S~VH;$mP5SSuQuWaHpiiI-RAOaw&a|`fhTa zc~PY&2`%`b?Eh>psJ~v37>s0Pb%!|w5YPrfyulQCd`>Ag;6xo)743sBM+Pexqa?`E z3Uffpg1liKy*vns$VPvbOu->vn1xI@B-PmzWUqxou$@&Sr(C?ntZ@jJkO z>-Cs$o6A?>3O6{0SWP58-tB1fscp>bs?&>7;Qi*p4G3Wy7FlTkcsYX`c%Lg1gNbw(I0NNc9|$pY`A100D>87gC>v=X zc{Ic|7A8N#HZ-z!EcCYIWHz$BT0g>M_TH;9NEXIS?=LgXk8-~wk$Okpq`N6tcfo$W z$?T(7aA3x;<)L56oFBD*>LOZcXZH(0dV9S~;5ujy09+Q3L$G$@ZQ0V@Q6+4-?~ z&vPa60k)E)l_s?XN?rY9TnkEg@g%W>8=`}DfvVKXmR5o6tDIcyt;m zjz$dbShB~p#UwbCDNWh5O_m!C2gh*{w)RMJ97Z$LP^03wbG0Pv-eR3ub?XsaYo0$yADsC3Rhj_*%)*F1i3g|3z^|kPdwR{QLIK?pu4w+S7EQ`>5 zL~7V3y@UpH!%ISA*2yjwZ(sznuMR}pl7WY z2YAPZ^T-7c1g17AS!NF|Rd<$b@R!QaqD1X50NY7&2HHaNK`D~FI$^}m_1&72U_;|$ zhX=pJfovvSBWxDtA7FfMH8c)D9>s4ZMcM3oSs#K#@kBnnOjg;8efKX2%FEk|*XTO;T}#+xMJ8WI(_XC&!S&Pa1N z9JPZA{T<8jSd*OBi+O^2oSM6}9v_dcO%UaePXnjTu*VV$H$*nPuKD!g*yujPa6~~( z*@t4dK0#mBq9}i;N?N$ulj3E8N-$MD!pcu1?lmNIt5D0sf>!j#Jvy;jvv>^o3P{wi zGvg(Q3T{K)QF?K({g~Fe7#gD)6Pp4**q+t^@S=n}oI%@mI8`hj%#yeSnQ@{eQs3qs zkTtby1t)7F{DRpmnoVg7LCN($wkIJrNLlN2LSGwI(!C$jrAtQPKWbUohwbVg8SYwn z?s7oUQcQTNXt=)V)TH}z`&^Kg2bgqy0bIqy(U(yT{gMbWrhoX6CL=~(s9P~}V2&D9 zh@CpQF_Q?JV@NO!XC^Xp_j4_aWFA|Kv|YNQQNW~%V*be5MXO5N0ipE6&~1JX8~Tim>mP` zv(ahr&mq6zBO{(5k{>Us!r6v>6&1AG9B-P$vdY)HV{&V~?nK{nRo`tf4m&}}SS-KHzQ3>`BDU2$BjbBs12 zzN3(eH=U7fpoT{+2toinWaggW-p0JJi?4wR`jg$Uw)T);MOFp&m|w$&Zg{fvfinyy zILBOf@Ob<*F?#RlqA-^obo43ojEiqj(g#Fu-)Y+XmR3Z^>B;eK1_F(o$f4E0hixr; zaLm!}u5nZpx&6!oO4%*KvV5!e!Ht}=~!!7YLzVXV4 zthh}bgbOGo4Ka&f5nqqAR~_<8Jc4axow-w=hw9nlTC9t#+Oka}reI#Z!Yg^h!Dp&ZW7*&gluH}icAMg8 z&q(aC1lHgwmUm;!qLJh<3)=x7(G&<`D-)e z163VT1;{p~QH5&Vrn7*X9@ zx@o~|F`wo9)nVGhuF;(%3>y^o{8y>xzxaD%mZGYz2sZ$!DUqugAgkr$XCC+BSPyBz zeH}nbe1}5cD5%XYh|A7B%_tncQ|Ss<0aP%1f_{V&yhd(HqIam3nS%mY=GiU$PPasA zTk7^`7UhhQkhPb@wO1Lj3=Ol>tl%O%W0A@yBo-SzF@Hgp!*>FXX3G?cYd59KPp~y# zz+vl(ii|GOM!6-*U(Ad*gyqc^>wk1c)4=?60bOuHT9e2snz{;y`hfi>A}Bym|NNG0 zRE=9NXdoa_^!ON)zitauGSUS$G$2z0+8b>F`vZ~7v=&YxNdZ{_<6s%A7X}I>G?#1# z3O=wFTHWTv*ewojB~#MO6m%Iw+a_0|tYT5CbhZyhtp+@h94FkcL91-Rvcd9dEo=5= z@qKIjaM_qxGXC44*WKoa&(qT;hsS9oq&#r53=K>UvR7C&CLy(u3h$#~HUR4)-a!{A z$dEoPdbF9}kK`PB+o)M^FcP?Ampm+*_E`joW5*Ob8!iW{3F^5RELj_N`y&DD+F~7} z+t*tRs*TT&$DYV*jzeT6dwIc$iM&aZjlp4s_m%ZEWx@rR(y5 zBQ$UAo;w!3m>Ya(qcrZ_v@&t4GTbl4x&c~dX|1~P(|F=;WM~xSivYEaB&M#-T5VG5 z;(=;>j#jFhOma(o`3C8Blm_=wLHau(mFWYp%t0`>%1tFg$iBnhn0V#KB@zIBlmA=-Y z$7_9DsU|6^<9QTn`RvYv;KK{g@d~8h=cn6RH(!lf3YeUu$^fYe)UlCd5%=I#%h+=~ zI(;nUDv?z0bCBo73GJ>v>W#M83lee+?hTID_!i#t6UU@Us~KX=HJ z$Zf0_HX=c93psUG8FBMkwTbskTCIalR#mLtx(`NutI*gs`rvuo0^@2W2;^OfEDO(5 zI%kn6s58=N*#V`~({y|2=;_s(0~pf}droBKVQ#y+_a97m!&Mo+hcB@)H$TI!c3x0u zLc)x2CzvuM(klnx4N5L6A4BGK1{%yw(bQ)-i)EujSj2**OOxB zh@Nv@f>FGS3H#XYqT7gBKtT~blx-(A_-Q&QtVLpQVJ}3VgwLWwnNYtg7LGh8B3t4f zKM<_BAPb1hT@6N`nQjdpoWA}2J6M)$r|-vl3yne|nMDH4!Hy-gbZ{yNGwq1NK&C{# zY2(tW80B4)VS(2PPlf2zc_qQgCA?v454*D%W0pa!^*)VxF$1dlsF{Z(IBzY>whgvOJ~}!O=o)}r$51;o(6*{JG74d1v(ewqs$4h9 zs(-aT*SO zn8w34qH%6$e0-2eQaAFcl<&t%OgBN)j0)M>lt#3F&d5w6j^Dfupnsj+anOo&e} zQ3ikpU8*)vGOF1aO1lEL!sc=`&}5}!^+4x*<~ZP7bSGppvSo3ymhtoy-)!xu;^91< z*`6NV%8tp4Z*k0sN(Zs4c873VbEs;|s@em~p3>C+HD4tup?t0KDJ+r62kK-ql*quJ zKwi|<84H!nLV-c6fxfe&jNeV=vBqry4WHBR5=`-GELe#+0|8@DaAbU4bvF)s4o zk&-+9Jnc!I6F5CClM=RQjrP{%8mTQ2qYI8Sfo3TB-py>{dtBUuQJx(pDVL776NrGN z#Ki~WplGW(Yx+Z&a4}rDc&b&Li5VZNwZa*PtKO~SrjGMjD-U?qUSGG#PL`0OhF;qs zk{4ISlGSq#V4rwnLZUJmrKdO%o{iaV1+$?kDG+Oc2gnGu3a87m>YQGO;Sl*EbneI=;Fq$2|U0kyVhwp`G^z!GfH9MFz?k8MlvB6k2ka0ip{ z#r3Y+*#_|+QigtIgp%-A6$nLQMN)uKzYD=+i_Y9pxe^bkA(x^S{?3~TP*Z}o>9DL2 z&23^&l|r-2E!l>S5C}$r!TY8X0Bw=6Md?Uq1H=&?Y=qMIWW?8!{6!l%yTKW9W;dIn zc%)3<6$f=`QgScArS5JvWj+Wn5`H`OT^S+I{V_wFi98av&3=YBAqldWKty3&R+hAW zDV>fQQI6+FjiI9!4yM~q9Q3c3niT8Al>-ZzEwc8xNbLKi@$GW9UNj7Zq}!f_+8lT3 z@3lktz2{ECV_vzxLY82tLSozdvO+0i26a5OISt9fe#tO{WIB(^$@HrNnxU@x@XiOl zy@AFY;MI17m;E|ql6+*opV{--_B*W0Ff?tG*$(tIPdMqLlPUzhOhw(&2nIMpxLhAeMS|Jt#=~wi)*(-f&}KQ46%re9 zuafyfj(v4>W~(EcMFM*W5Wclm36!5}zL&5Yemm!!W}KH20~MI4+SzL0TOr%nC+D*- z0uW5?nRjw%b-(4CceRtxQpVbrjG`UdEcsK z(>+Nx$Xj|VoyDW`Yo5fb@@rnia|=cpL=OG3dDrQXU;J&HDUag~sNJNrdm4cd{4Hh7 zQFQA;3DOKp&N*Dp8OTJ+O8At6^2Fj4bxp)IsMV4E%pmp#ynH;!z}w%>HQ>z^iF-}u zw9mXAH8gSped&!Negk*6tx1x#cYf!N!+8B9+8&nt{N;s3uaDL}Gke>|fjd5Qj_NSi z-4_d2l9E{6#ATZ6v;fHfyn zRlN7f#%gH|+XKTwXf(QM4CCBkSt(-KIriF#qzyJ5v{Qc0WcE zg`6sX|8X3={qO$F{Q1P;up|spfM&GZ6BA@caiktv3j8oR(RngrX)Xh!+ykpi3@QB;JZgER|bZGMa!3=n3C%p&EcZxC0|2i zcT(?~g4ylZAYc7(Pd0Gbq?TO;5B~mh4WlskVv@mFWL&Dfm!a-$pNBqDJFt(tm@OZ0%X8Os7?8DeD=6{aCsv zqS~U@nAlA<5$0;E#XOqy1^H)k(_9~tZpOkzFPd8&UdR1qpz5vrrZ!DhYL{tCuyVar z6d$u1!`(rLbU**Lij(MBEFeW_t5qM+wdXMjCwvy*a=B73z5dt;J|ANRDW^T5L@uCO zu7&|IHccR7IV(CDYOv&p^1*iO^0Z36c4lOLdOpg+MwtN}Ztz{ozp#vzYiuGVfj~I? zbbrEd(fN;fYa8p}sL0)lZPIu(DjUWqlaJCU76>=e!1>6l`s2fn17`f$y_8)KpigHA zmD5nByj0^IE2cMHAOu#B>(0f`x1!SFko!toJ*=h=CCjsy2s7BtWU=2Qez?mI65}P! zd?zKb9chky!gi(81JUG>UyD=>&J5jYHYkX=L8i|?*@LFfocW?Ed%9=o$iyo5$lo0T zm)=ZTXr2Tk6&4m%35be_zGilN3zgY8Iu1+nG{)PjeIz&Wv@~CSa(|U{Hooe=wM89q zrYIfb95Gqjvmj+IkHU@=!ZvHp%Wt%ikdKT)VMq&(sMBdPBd;LLkKn{?qJKwVF^yf) z8;aLa@{ARu$l?@Ff|r#oYMAeSPPy_>m}BgJ@Gk`SWJ#Zo1dsug-Hh9zXlgRyXMO48 zXT*ezq-hQ-9vp=);A_PpS?nw^`_Zl z^`5jpwqRuH8@w(uZ?T}2$1gJir{yNZM&OklpND)~;C!ebn}>zP&|F?C4c>&GYLE_6 z);;a@J9Z~)1MHhj7%tqlnTK(!nT2u8sb*3Ws*kqqd{5{t)u>C7hR`NNBsmY$)jZFe z@(JoJFE0jIs%``3E6k1CgPz^XgNLl#^MWa@B*4#&?BL~>s;h#{EL-coL@dSJP)P0p zO(%3)Liuew3jm$HBlO~>L8Tp4hY?&FJS0C?yg>d)2DDz~mWsAUe-R*YB(x&@n$_1D zqxo&h8Y(sNVZ12DqSTB%WIV~!)N0te%q$B!bxOWR5cM*x?^5Aervp%(uh&e8c3FXWS%&Ev+*|2s;MQUPp*u{2T=uv% zbhoASs{x9urx%!wSklA;_TnAgTnu*6kTsHWT8!K`AxtxWwz0I_PMI1YYVra^{Th&b zO*tzQFzC9+dlocVJ6z4eP|MTY+c~KEh=h9Xrg4sl1{O?hKw1gCK?Os(1EmBpDukdK z){RcF15G||7(=oQ;h#kg7wa>~2r(&G_<)>k^`4x;f^4yE_xg(2iJU9x>@OCIZlARa z@|KbFE-Jtf-183l-^v<&Ap+u4Z~m)?jQ97uH%vcK71o$*l>t0wY*d!4(&60kiS_`4#Ed(gnjHOv zy}SV4A#!l=s4@=piI9oiS$l! zBKfPz1-C``U=BjN9P8i1&OENe*Nqyjq25XpTloxiE@{SfbGEBJjVsO`TY$XjMgBgy z8ee^a)K)7``i&nTICV;`{BPqdv(}v*)TqPI>6Tuju$4j2B95 z_(H=|eHI?3WKqPL`v`@WEe_QV#I74>^<_&0CPALc@Li}Hk31oWip_Lsd!k<=?r3>) zcgXda+dEAS;FU|vQwD|M`v6!oOrx?{=^z|NSO!?fnMuSZExU$MXwsPMH4D5s8EnI| z0~?DvtZ=mI_yD`bQOnf#8oamalLd!O*sq*8M*M?95k`2Bl+P?wLP8KtOwhq={g z;uirvqPuV-jQv=b*XzB>WN&DfgTF<|`qjTsPIwES!l5itdfq<`TLO+~MnAqjTUZ!- z1hY`b1>TOI?^DkXeLyGQ{Ah|A5>gHfKv}sH*6$X7#k zuwqR?f8J;OC$5nHQ{EF_y{Y)=Q-Ez<{7aKk9xQ@?=6ELzjvV0s2=2$9B&*ElY2x-K zCP3Z5!dcADQQW}BM8U$u$b`Yj+Q7-FLRr^tjtPxVuQu2e+vI!iU=GuA&IJ-O4hS(4 z;m`RS1ti0{ukBo=O&V8vR(ustd2lo14hHy`!cp zpvt{4SV$+)@xA(R@C@o*IvR=$C;Lr64~g(jluSYAn7*o2I-D!14Q#NIG{vq10i=-4 zHBnyTiW<(Xc|5Jf;hU)T)o{d)0j=tqZ)hLuLUddH|JL$RWMwi!E97K2MxmKQ8j2R?0!SWTLfreVZKM8>UozR0E6gV0qaBjMqlyz6yse;<4}N zHbtTtvHeJiIDk9C()lHuTu3v3b&A%qjc>lzOPiO2LZJ7?i#&9&A*n1|@r#TeAzlEf z7wG~>IMsBONft;-i!hpQ+OGucgOT6r)l+OK-717&GJW~S4?t`@QY&H>U-fdA<`Iyj zg+yuq88kth1jpri;{8`uZ_7ysEeI>jko2frj3p)_#jXm6e^cp%75T=f(?< zCU)N5Ty`#IxMZ&eqV8QxMAxem$m?JU8t;$f$i0F5M=5^Rko_q}5cw1-b?^I+`#&WE z5Pw99FPRw_m^At812#UOPlP=FdpDB^ZL(jK>hyQLrGR7OkYOu1R7&&MlzH>k5UU5>?0Ya~b- z`=LW$uPpAtxW`y<;>jAjrTHRNv*{kfBE7YSIWt|*sYb-Y-7q2GrwC3dN$`aKweph> z-3DkWYJBcjIRst#AmV86ru4HRxI{i|$-BVZ<;_(yDwjk?tW!|z&}0ivWY2L*V2>oo z(Y+r2C6>D4$v6*M)L?PY!mVbDxF_!EEGsZXH`hit-3p4)=1}+Kuwm3to`g+BoaiF< z2ga~rvubggg{))1NJPVp*=&cf?>Ii4LF&$lXe8WIRNy<8*=}b}6ZXMm4Gt|S-ueJV z-{uyI3uxkx&LjsqHsPxP$BKZj#}>c2Mraw}6CXXOf|cCa&gwpJN-(Jk@#kyIb1(F1 zz4Agno*A*YSubS1m9d$o9Cc>N|{gr=AKveBVB#{5rSsK>*DB; zih_t%h@^AfG1e|K0$e(Cu79Hqpe8^iL902MBbOgmi%q`=wji3RBuiB03Dx?eXu6cg z_+ZoP^!W(UqB-0`>~{#Y29|ZDUByirE=-D#XLfTPjYnZSmtrge_DbZquxiXw%LIV_ zBP4$UlD`EPGp|CQstDsP`d@fc^6m}-|2Ny-_#Ar5^G6jGCes50O9SjK7Aq6pN>K54 z8AVngl#VE7tcj68LQRq5cjE@0bIUg9Tq`Vi-Wjk%u_A+~-W3O5Mh#O?1R{K!DW5j( zCi$KoIgw`QVYqV5F#|sU%9MhV_F&RIxRK!pbsk6vVRj(%>TV8FrArH(!af z_st~{-ai;DI|VS!dIA1gORkcIpJ$%iZf_EZq;tRZAzK}St6rx=@wTjD0+3e-vE$k* zuOQ)OmAuLxJcsn%A5A@H=5tRFE@E;OX}$@Gtv_zfIIkq_tuTgsuf#u3*G*O{&;V2o zP17_Wj0-Ef$yUk3`0qX79-Q!4(r>YBH2$%OGtKG8si5ggfcF!Tcy|1$Pc{DQ$mCouvPYTazFp zFy^P}Ytn`W#sT>kPa}zb0|EsCT7`&Lh$2t!LIcJF{Ihh0Dl1B;ib#AM*l|p7NME5D za;T)CQjmKIzJkH}KqZON5qPJ=aqJkzh1PA~Qv3RKKIfTKk3tG`N7tV7qy}o3U=OIs zx=nR#6w5QFUI}#if>!^)M}JGX7{t4D&X*74DkwaF)$QC=9Z5?z6wERyXecp+9#bk8 z0o33O;0PC3CrYiGY7A?-N2t{dzfSsUw_Jj5QNF-6<5kLcOEAR!zgd2NYvq+Jj&6;@YyYK)X214KA zmJ&;a)IbRV*Y8f3QBdE0=|r?ZMGQMA*3oYcb50|t4}6c2S~0TdlLQ{zL$AZd(&v5c zQm%+!g4Y_=o!)SN#t}1E!KaCFqS*0qIo)iQdW_Y{c2bhXyW@V`hdNlAWA!9bEdsvu zGv^o}3F8FEPR9%c2g_Ppq=+f?k?Slnk?USrEGJRUHBZI7MZYu4+>*)zG*LZCv&w6! zGT1ULLcJ%LW{Ai96WD-?p)*dF8LGD1U3K&v?(ZxHt>1f5*^38Kqz~W6>9@d!M-S3J zj-1(EP~6gu46EZYGp~cxg|Um}MF9dnW@w(~zheZnfZ~X`?7q!0#6X*txEg(}A&d(&mEFlx~cm`|GxCCEv&qwo5e~B~t5r>x>=y0#lD<~C5w9Fik zNfLeLT=pf0S*kd0HBxO=({mr62QuOrGT+9(9NoPR{W+$-eNHJG*(024<`NK#Wk8r8 z&Bi1*Z;M(w!cIrujq~KAiRiycQVemNp93xITZ5wI6H;;0dNxz~0vz7iO6*UL~JlOu2^(K(`Df7?W zLI4o6wzG5mpDm-rCl4Zsbcz5;&+RgkJeyyO_he5;N=yQ&AYsQlFm=RO4010-b z6bY6)pIFnJDkhx!;?3zGQCKF#j}5S=kLLvE^J0YG`B`?4pPp7TKUiCXkc!T0$sVmG zQk1oZNgRZ*%5+Jw|vewmWo=qzsW3unc`M_K0R1`TP2 zO3fVYWQ7e|4ngGR>UUDAByY#Mv{L$Cz@m?1YnG01!Q0tK%r8P90)U#Pf!rLh@i^- zDLn5q796vo3|uHB8-;Xpa-n(RMqJ~y?&(1PcfxIPY%>EyF-8c_l#})ouesEJ1XCmY zA(&bpQkAfc{}JmJlSb__j#%3c4y(PAKr+}-e&E&>1HSMid?zr*Qa;3x1xbwD0mk!E zP&3#TAfN8VUuR@ezGsB$NGUpRnOWa5BYe^9LgF149KszY!dv?)Hf2%`_QGxNxN1 zZ~YV=(YqB1>oOyov@BCy%|V1Zj0Y^%jB<%x{~Nt0{sex^{|9~D*xpO<*k(cz z7VhLmkswFYcP%=tdDSXF~n>cJUiEDcb_$EA-T(Z|l8?mC26SjhMw!TmLP* z1u53nZGYIU0R4|OMNZ~=!A5SPzycolboH7pv4QbFjc_so9IgAxMB@AU;D0{sUENhd-siO*lY69RETI0X$%sWcfF2$mBJuKYtsZD*C%!+=MAd zym&ktwU3m|oyKpM_@aWvq6VAB8fpvJmFePTIakVb3-&e#Q+C;0L-YYNpLxg}@U3}q zbgedO#DTD!TMQ8}6_KytDqlsBM7J|iS2jjW=h)~klAWgboId`19c?;IZvI-8Z35Du zv*bPQZc6nI8F5R+GX>o8QEWY-v`mJ(G;e+<^({t`u2VZ7|lv|T?K z;9b8MKeF8 zdEtv6YJUbLII05N??UsA>{BPbg^px7m`_v z+CYX#lhig(5_-=(@vVH^QNK&OvwY#w-|aKv6cws986i4eVy&!c=8)=$qGlO#HIj=eS!+T)(iOBFrkn+E zj_u%TGN<(8W4-aR;9}WQX0}(=oztX9obmIk7vREnx$ed0^4AocvkE=YHTZ zfK8IX@w2G}%o(Wv*FJU@VoN>5WK+=%T*Zh6wR;(P#hkHobJw9ZG}7FemX1~_La5FET0m zN?vr9&eqH48FaP<&Q1Hyt{hWo9P0@)E)0M(DOoM|6)95hre7vih7;!2PM^$1jsVwv?s;NG<_i1tw?A0C@cN-zOf=vF07zrvq-LX zGr1xe?>vu8qpNd`dw!9lAyj&hNH4>^bT4ffxiafbq%x8v2gS54cPL9C9t(;$EZjTiQ6~I7hZmDRiX7(lsQ>cT=@lbL0G{k4NfkR!=L32?B0OH{2|$~v;;%HSO_3xJkr z&mhI|O3ju3D!%U%)W7T(fEe~itFE}Utt+&`OmUf2k_C2h zR&-9aSQNE^*dW+tA8Ig9X*1Q7{vz4ZKhKz`(6xWAHd>)ZLE5`=zvhbn#+fMvP(hj? z{HcN(dg$=GNYP%9^+;uK+##ILwqeNTv3Y}_)G?KGLDy;BBD$7Osh1rvRLw{8xNH@T z>~&rzzJS-`k$o&v`$LLz1`8YWD}M!0=hNSq`L)`oX~9|g<>yRwq(|oX@V_Z zR4v)4MNfiJiA3J)?$5XsONRx?d5!gYvdP-!6UlKR+e7AYDZ|Er3CUg)2Rq5U?%heb zyy+tz2)luG*vmetb$Mn_zujx1U-!hfV|~-tP>;KcvyWIOUU6*vQDrw^ouS1{ z5;$cewCed#SN?KdaR7ZH!9Aq6MA9o45GW2;R&0hmbT1`>0Z%kQ+7Img>faUni@{{a zen->T-dQwsSUtU@rW(tyO570FY-GIOPuv&RwQ9E?gF!HhRh#B4-_=BazM+K=lBF#h z$&zX$RNQen4&9aX!y;s=T4W|q@6cz8?*yddOD3_$SB`R%gumGJxBMcqJw3LN1&vL* zzb~Je!=BR-N!GXn1oT;io2K)$O9*;~(s^P#-N2-kaA-^FuKb#htqJ1)J-Sm*XMEY= zY!fu1E2YypVnaD8s$?l;{lZ9u2S}IVnIh;}dz{li(b9GUUAH=`#JxaM{GkM+QFvWo zG|srRTAL8z-PKaq4QZcR;hTJsWw`~FRB5y!t=rjZQK=vd2-FiFJVCeSZxClt3^hCr zFH+J@;8Jt>t+DW&(-H!!d`*0(F>wFk_@Y55M>r<$`Rn?8`gNRnyo}tG%kWfc=$@3T z$75x?g{y~9_B-avHVH_Z*!81z`;bDrstEtcrcR6nZgxB4SXZZ-Tk6LSQ zE4kPAn{&eNfNzPYA0vN}-Je-1I9t|xe2YQ08`%~5--Z1tE4JtMs5SV-1euBhrndbm z^tmb~|3sWr7nPhDh5BuKzuafl*S=3F!5Pk?#P>P$L13WL?59fKO z0y?XrcmNR`S{U)DW?u<1rcu;#_^(~1kfBriLd`YU(oJ1a9lg;wb;bB^N_v5eMf5jo zvG#xkCDZX%WUNeu&VFua?-&|=7`j>L!t3AA-O#AsvU1gD^WEPjp&2;8T&rKJ;yiQhaZA@FBK1LNB2(+lG9)mwu=L$>eK_&F>H@#=oO(-q&-x>M&<2J6v!`>!o^ zJt z{;&(Ww(+L?;bh>Axdppj2sBBnk-&bpCnhFnHe1hflgDSP(TGaeH0vO~vk~c6>Neo;q@z6hMEMc@MT1+A$zAn|bT3JjenAz9DtG7ZngG=~Ip+pvSbE zg)&(?cs%3&Gv~~x{#e75{VWTh{N^MqX4+d?a)NtKsANBf{)@&$ZrLi;(Fy*{L2C zMr}GI%5>kQOw1mkQKG75BI8m9>z7O@AFsj5V_+)2a`n%Yrtl>GA-Op~3V$Vf-6WE3 zk^Yi*&kgU|QA?oUP>H_>s46i(V*t@+% zDfd+SB8485aWr0}adIua49EKWeLuBppQfK0SaUQd%C~eIr4m5xRo9cK79HDI6iyNs zQ>*~b+BBQ+=}T~*iHqdYGt-?MDa3&EEtQsLeQXaicOk;YFa$+Fh_dO7)LBO`?nhd; z3&BDW8~XQVT0dAC*F5b3hIa7*wobxsQFPX3-2q$TI-yG>M`!`4Z4>k={i-lNAw5wc zQADiT4m-Zkr*s*5Qohn%B81XsV&4Li@HUn8&`lscWd}sx@;rHrs|^LgWuMVnJpR(n$B>u25*Wirf|5Hu&tfz1{ZTmk&poR1{OXimGm<-I*W)!n4(I> z*u|x=O`nF}^=B8xra)clH;}Kfgc21k#)WKEl^fVJm?uDh_k!K2XIR=xs58$pgC=fN z&ojSCM(4Z=dcUrp&$#cE`fJ*B8rH^694G>$d!@62j~O1;aL^_$bF*@aPBLSiQDSGa z@4`2Hg{*Yk>6o5kf>x2BkTQ<6e9N@;HcKcsXLj9-ca3HCcMl-)9+XgRP6m`{bY+73 z9gtd3y#r*0uuR4kdLR2Y7e4i6;CyIgyYwebk_kaKvGMYJla$`G zLqK%3iAe$c<~#cfil7v|V)fC-^p4PhRIf*i#x?eiD(EV=`5~9JmISyPmK_;>BfwqLNHa=1S%$%|^Sv8z|k-DEk#jnvVn+bmP z?&5H){8SZjUoE0blBRkNk9HpC=)ByqpUV@6B6;h|fl|gnu~ih%IW0OPpTc2y)seHBcW%?j$5sl*IHTfB2T+uYfHiGHI2(ep z-?_mut_K-Nm1Ie-M2~p~R___M$~fN<@B@(q?I2Z0$*w_MP`R_l(=j|9wAipU*V+ z`98~e&U2o#+;h(zcl1>@&lojZOB>8*X!P{jazPBcPkk7J2mRUN`6jya=HJ~qvzQxOVje=RA*k%NI#=_Xw{p5i!U3) z-zrVnqm)ypm-=RJud#BCXL|Ryxnac#Z-;La#GhKJIOE0olA|+|t0wJiOn75K-Aj0s z7;rYHbe`_grk_!buR6~zSBN{^92nEudF}IA->w%=Z~RCZ%h!6ueOa_dcT>G_$3?&G zHSuBFhwIE)=&iCceO%O}_gaRV{B(!EXfYgRd9ZLj>K-1IwqTm^CDxW+_p`xK1=IY7 z&c3*NMDGDNo$FcKhJ4-n&LVkeux!_g&k7Hho$&NKA#izU35VV?9t2cJfA;@qHnsfv z)1d0O6X*agghYR}M$C?kS{~m3jTrZJ2TD{$D|LKcm%ZH*>mr4kdrLQVN=;UaFCiTvD>B zUk(Ady9;eGq(Qv)Yz`)T#mQp;zV z6!|QZFh6|r(SPTw@!*n zsqzTE*j){80I<1HsR>|S%w@mN)*`@Net z3tb8V&JFOM9`(dGJILF6+NtE2ou>D;&Kon%`*_Z7le7UxPCD(1(pJkq?PnYp9d2^T z{_vA|dngz4urkx%WgYoWz3(n(vx z!&w9EB9ExM6!`N$dxRS1nimyrusNhPerkz{+fjv)B`?ato|&E0n^|Ey@0LOGjq^j{ z;bY?26WJAiGHSY}FTc6!@OIXZGl{9Q%-sWy6dr$=a`^RUDaU=U?kjtG9$%nwRL9{; zc&m>6p;r~9GV|T{U0%pJ(6M{_{L70^o_%_1!R^Bb#_3GUp1Wzy$;U>|dGI>Zfi;?^ zEmJ0_1YZtk1$LiZGu3F?KB>%YnWK&R`CU#PC|^ABNWGE!%O`#lC)C?|uAfk|fAXsT zRI6%s}=Gq!$uRGo@QL0iHI{LDCX>GM{+O(*94aSx-sWRVY z#OrvX>u0qe<-1tUf5lQYs6R(tHkq92c6z8(+0>5BZcC;v8UJE|4eg&&P{P#eM-v%jaNFgNkR*d1lj zJEli$yck+=Q9J);=)G1W*VxB}9$81u#y)*N>;8mm@uyEG8y?Bssq66arhTHP)z#Gz zWjSSL&z!0k+HG>lwo^ABV7$Y{H|)l%ixXV#-Ay}DRr}4o>)X3cTeIaaug(}>+99P= zeCYnzf)%rs9FWGcEvf7urO)bbU+2i?AAec->ZDw>*St~ZRhO=NxN=bJrfVAd2U@B$ z_l&9TZ>H&^t}fr*@-B@COsA^M6PJvq0fV}~dEEC@yY_42wxLNGi3wg3Yil=b9sNpvO>$JEiTOiK zb;0IM?QiFwT5J`2>Q~UDrL*!1eTScqdvd`tT-q+Uf&@bbj{nR+kVQQ z5gCt99r`J#2u`kF{?+)?0V*edz4_qhyCSR8HoS0X*z(9juUYMH!UToq^K8?XUNyXE zZkNzve(d3h=W3fb&C!_>Pu&UAvisRO;8yCL$b7|~wK@`uhipDlpYt?xNX&`2ulJgD zKb=nYc`bi-@8&@l4wZH#?oHO%KVnaDt3h;sL4QHltb5wg0|fqOH{7}U$tyU<%6f2d zeo?}C?XQZP?7Jl{|KPTNRDSZ^*5mi&vZZ?)N=iLW_v{XHo^a{hdDHZnmKTQKIB@iX zUq8P)OCBtFF#F4*=8krc?bmGP#q6Kbv8qdtjMD0T??)yN(09HAzkKyWL+r6a-}o$i zpgE1TLOWc&H`!@ud2ZCUBjegqFHPq^9W<|aT%eh!($hgMcVkUv-}~ZYl67aceMe{Q zQ2ShsjGU3xsu$foE=uozdNzKt^huN86n)CfOgG`VME*YNrqar|hOp>!L&i_^{yKL- z>X8kxSFiAjXWCCRZ;ZQoIp^3wWE~ff%p3eAxQRWCb44((WLGB3CDz_bpwu=<;r#jV z7s}5Dewi}aJKuCh`?H;1_BU2-c#2qh6X%AmUw2~7!*bWg!a2)Sqwmj~Sanmo$n(5~ zi>Zy}+kG__9usT>{c6uw*K7Awr5vl4J&|se`qQKAY33x8yXjMg&hm9tf8%~<6KApQ z_~d<+{t45AinotaR9on#T(Z|D+Y9BYmc=fPHkD`yZk?joFv>AK|L~EH(amR$RtBD* z5?3+f%`(%SfltnTeE8q(FT1Ag%GovON@rodUd6Bkzeka#ccvTrJT1x}voGdg^U=F2 zMn?u)*A86ncQA1OS8o2sceaKN2etTU#+;oF`x^3+rw{+>mj8C&VMD)ztCtzaD;}89 zG0l!O_h8;3gKrHZ+M^ucaO^yjn-%w+bLu@y_8q(S%=vu4k&Nh_pC2aXE<4wd=6ljb z{a!`NAKl|R51hLculdbA{{F*&O=z&YPU3;uZaU0#BH zC7}(apW7!!$0jda{U3IR|EVtz>I)<_tYhykk>Jn~cHy=R1q14E*X|5_rDOeoykz ztLul%Y|R=kZKyHXv$*oYg@BOPKVIrAAMwL6M>|?~e{|G0wVWr(YxDDL!`?@1nKmUp z)$@0@yT>)K^~+ACRV18DYiVV%E@gil z_9ytV-fZWMuH$|br(J4IK4q8p;_^Mayi}{_adtiFNxaq057id)d>7w(yfK#5oB7c~ z@z&!zc`g=tFT<1q%l-eTu9uD|pIaH%o*x)A0d~ZCV5{#)#qC7`FO!1O-2BYc zPFF)x0}h%uL~2X!Jod3qtWkCkwnr^}=-lA$p(Dj9h*~I@G|VY9=8o%*=!tuS z9PVi6=HKj4^ID?(J7~6rrE+IPvSzifU+W9`9dOLA@_57$wf<%5pR3-_d-mh*+}$;| ziYmv9o4ui+@j-77QIwFL?z;8i_8X=v<<v!dl z*4r(=6%U*5S(u!WSM<(I%`xuJ7!zrYw^dW~0!ANXEuI{(Gwb}#-9hJO+bxx=c+-^p z^=#a={P4&E$HVWHAEh_{jlP`}{{6}4S5{9GuE*V8FXa+BG0*dI?U#6`Pp?`{QR9DM zx+{4l4NC(Z{+fP#(lUSh@3A@auN8ldpEf3_sV(~E{BuYCM6_E?n;d-ltJk#erOVLq zrRB>qj+<`XI$Uo8IwhvC5 z73VKJ@!sOdR=-6m_lonEoG7!1aD3<#aN9X{X+_3tRkN|ptL+rFF41-<)qMLR$)ZX! z^4jXi>XDJxuMBD&WAbIp0_l>RJ+1rpp|frldI`oy9xqwM@49S}o)oXK$g8#STGkHL z6V=Dp*)BZ<53{y!TcPl0!w%27^~&#^65m%ke+?_2*sDw(J$2p1?Kw5UQRhO{)TMUe z>;o^Pf?d)Q!^eEqHn_WQ{U|x_goIbl-WRp%5|f;h2mU=|U6*2AcfbEfXOCY|Gj&gD zWyCqxZA+?MKPKdowYT5agkb%@2dwK-!<;KWUYz(Vxzd?6GdVA+=i>&uHKQ(Ad!NzD znCaYql(TxJ^OwC(i=x^C-E}^B275AQ^P&pnx&Nhw-q*9N zdX(6m>fH0S^2g5MKb}-3NFLejI(k6s!H45yKmEBDYVo)%bB9KAg8Z>3k)>@BV~vX< zH^^^s>I%DFe)XHxoy6Q^?YM-o3d*4cI#(&Ff=d@nR6ldoKHHAjopB+|VEWbmLHZiA zHv4btI8d#)a9sswXp{cx#U=iWmDsaC)K8dsx$$n<&}jP|uHWl?tkazCj&1TTh|(Q> ztI2RUrSxe zWu(h)>ckH?>2TF-qUK3|{f8mh{+lJ~m`FNSV;^dXAyvV?5qaqaie^bP0L&YkC`R^4Dwskc_3_Y`NmkKhK{d?%YS9J zJ8#2d{_K9cZ}f{!$OFfI!pIry;P!-kJMd=%irfsZ15l;FdKk1~8z;G+s3HTbB*M*}{Z z@XcP{?#AiQ{!vmfp{@GD9{{hdHM$SCoS<@GLE%*Y|`+%oQQ~D2i!|99AhrH?Z zMdd?Y2z_Djh&O}2NPWZ$rY~MR;swwb!yog!>5I(AJo?NrdhnP>p9Vz(p7193u>@%Q z6CVA8ps4Z*Zzc`vKjnqf7aN}PX3-a&PkD3b3;$=lAo}9`Gu~|aLbp+-!>z)WBkc#jdMf#ymU3 zeJ)hcdk&y#1P#VM=V|I=KX{s-)|+5IV2fmIpRe$JC{-#7Bwf*i7d%bcnI5dZEe1eu zR9?*|P9(knuxB1Jc+GRoQizpDtuKV7bz#neg_tuQO?}CufA1B+FM0~7gNrcgnRRKA zDr$SlQ=lCgn%jSr1RSzk2#)xRIbssuCoY2`UkME*y#hmf6aH~JfkPWg+`T$+Fc^xE z>DMn<%#hY{EFMGGCi6Au!&^=OOwM^DRCQ0e>tqS4UZ5)OLu?8ynU$F$i?+NGR&n$&dhfQxme{DJqK6%U2A#IMq z{+U@HGu+Ypw>)-#`qZ>&iuAK)tm35NXM+LLteM$z7XQ+KoDco^c*i7Ts81HS;>sxD z#+}orq(!#?U9wFZl-!Pl)>P1jHl7w;qjL@3C#Qm$Z(wGGn3>?6jP&m|o;q!2R|l9; z+YOBVXwrKg2}%QZRohkw${R2vZo;3I%o>`fkma{q1GQ=iNIoQlE!SHCH-x3|)b3v| z!oH8o!?r;~1#RvS?F{Nivn0-&qLuAD1?Gn%(bjgJ1~r{<+&=JF=vg~Yo37TsUlQ!s zZ?IUkiVA2$ATFRK#eUyOOfsejBrUR{POG8v55i3T_ftRp`q_v{+n)nzJH!L8X}k4; z&7(~rsBHLQpiyFye=gA;#CGuLpL<4hP}g5Y3p#lwsHLygojBCDXw)7J?-XY7*LQR0 z9fLUIUr7|V+E9%ROd@q+-dz9R+Bel;DLbUz#UnpXN{=)fYqNYm4nUW>crs{ym#_l= zUTgnfBejgU0bN|f*d!kpaOfSUU%x?ORh@aCF`VW3fFqK`|99qFGMYH^JD-B4waEBO zvi{$Tpa0tdols~u&jwxt)%yRI@-G>1DXPs-iX)2rD6DhGml=`UAiVf>emBM+x>I3E zXH@@@r$UeMn-2VLTm({cVe46ZY@LQAKJi>o;U^xSj*i$Xe_}Rm-r~{?|KD%_{p;^^ zsOVXVI@*Sml_mP)7rfZ!%+y3eBlaGcSUH{lw2Z-JycVFF-Q@$eW{UK`345CLH^{kF z1kGygVWFgN!an|^YOCo02uuuQ^iVP5YMrzZ5LZPXzz|($=G`I?cNP=R=q6^zR4R5HH|}_nO>MN#9>*U_mDnQ#7GEoS58sSxqpyv!yWrY<5XKFWn*`s2iWL$*%6t~u zEdlIOArkypf`fixM8<(A%60OR-QPMs^92UW#u|y%G{B`g~awA_;7Z z!Ni1*F(9QFSxh5Z=#M1dmO3>US9bzhCdD5_9Ug*-1Zw;+tYe3Qr1`_By~7D{OPcRN zJ#ZsL)no}7bettnKt)P?DKuS%&!-kmBD~;m2|eV>=5x`wITBpRCi3r4YTgtguyKxr z77_521-+nY1kRP^yHH~S2%#Xyccp5AFfkadmgCz|Yi1In0~61}FcCo|hZFH~7T=ND z8%c;w%ZYt6>TC=~3{fVVA5JO7GK4-#;qf)lBzY+Q4J=2o%+<|sYrs|kw{KvWT1Md3 zG^ovZMS#oG#cIP{!3by~DHSkxQ~~tLVReel?aY+mq5M$3Fha^4;JsYK@Dx!92Z9^1 zP6VmvKpXVSB1rRLQmz?Qx1B+R1=T2mu?0B<_AZdHp%-AJDaI)QPiiOOZBpWoq5^XX z;Z!K0hHl|@;c-Fc^+5td{_#-bIY_w_E@Vekkq8`e1;+AT3~xHkz*DF}XBk2dy;tUs zr#_xz5M7k0!ndKeUm!@m3g3^Kb%|lK;3o>8dFH8tQT9~=SE}-TsFZ3#K=u#Bu5eM5 z8n`*^Is#t&_-VBP{8B+1g87XrMFOS6^6GxW#9q0 zdR#P01ByEMObBa2MDjHFL#WQzB8a*sG*4HRGF5wnIV*Mf3Qhsr$bP0$o`dz2kv)+aH3s^7&&ai5`ZnhwkvfZL3}eVIgAy ze>inY0zDV-9nc;%iic&ms9FFO87zh2XzI2M{vL`h@hA?Of!Uh{lxUA^l_LVbv|%Wa zlt;D(d=pe;M9H9w`jjC`(Sfe^fFll@;|4IJYPsUD8d|OkRd}kxz=}v#7kb4qBe5du zR2cyQ$;MsAVgg-iM4;Z7(iRzF9_vBHBsDP40_p4Xov1%NhLA>S7>P3=$do~p3gR8> z>wD@3pxQ7H^X4E`J-!+88AM5;83r&S-Z20@T@#|WegIz?dGv=$SDA|-=P+VxErJ*i z0Az(7gSb-#4unV_O9@b;0ff42yjZoA92o(1lr#{MYyD7y#CSscV{dZ|`MOjlyy=gt zIMEP>hed9W;{9!Usp7$uGLi~#x1Lj*}Tf|^KosBmms)+K(_emwp5|g^)!$`>>3lr!Ljgv%>3=^39xPBOc*~OGEhuTf}gQ)>i zMUX#{lrGB9g7_>jg;p6bjp1?7VU|FJ3}Q8yw?2U3c~FVd8G?f%&0w?-2_#6F8GjOW zGYEy6L!cbYAvHNOFcCxr(%-hI+ZYH>Hw< zh#SR~L77&dP%1>~2MeUp-dKQJF#P==%t98{fD8&DmgigZ9jHY@0#1%7p<2v7Cqz_i z_|{aHkf>S&%Y)fAd=ttn6s6lhD@+Q-L4l2>C6M}mY@qE7!x%&s&9wzn4g%hV<%G969Y(OYL3}fbDC7f5Xjl#a z0RshGbagydjY zd$=J&%oq%b;FwDYb|J+@y4ykf?qJY1+)Lo9A+Utw4uLM0c|Zi2Hv}SRdxSw;sLdxC zf`uZgz*z1BF!tt(SQUny7LiJJgjO#)D}rpk4)M;_hdvrI64qV;x5ShSONnU8Ef`hk z`v1HuCg4>?1oZELK)MsOPv=#k^+(`PsRuYD-zcUMa)S|IBfFt6S3IvH$iBCfJgR&F zT`FTJSgO6xz$(aTC|Ek*DP~Ebk+CF&tcO7s?tDRzq+xt#O7jgN+I~=)=)*9uDD$2m zkN;5gU8S(nQ=K9Fb2W@r}T_EPyXc!-BQm9)cE# zd4GNpUZx8SwL^LdaY+Z}!H+J`az7-I0f?b09Z9%h8V%5COoA z%uK{)qZ=geD@zf?)g3%JYDW;a5quex;vvaFAw_*jbH*L&?=VC}pwk@&i3_ms$5jRu zH!94P5W7b}c#e)lsiRI6BkfJ@)MwTm+J{!G=a}XdtXYz8WqF8A2YBUr333@ zVfm^^Zz8a3n;Ap~&7BBIGwqd7;SZE*^Bscs1PeB`F|a0@h@eKJJ^6fzhv?%3cxbc2 zlRuGK3#(;p-Cs(IhrHH68`3?M;{{I7|4Mixy`a)YKMAqN3$kP)tdg;op0bo8Qn&zy zHM~JVg+j`~Fx5=(hEWB{5F&~vrGr}2L8cDN*vb=F$_MC4}S#3 z(jdeK1_nH=4vH^Oq>jT`<$%^QaBl!`SvhzgpJB7`KlyhR#TvI=SLEOjZ>xgXyp`W z0_Cv`qJ|z$fdPV=NDxCm2vW2+Ay)Xo!t&{4LY#ya3h&H<$hqnM1I%Z`sM2ll57;!D?<#Q{eGG%KX_H&FV{xTjAiwZJR#63uQHkT#o@qqavW0&kdmgR2Tuv#(TpE;W|kg zw$;3(RSi`iVhCX~7n&+L8Jtd81fBg?G}L;%IDZ&n2%aV$#9WUBA8g}K#=icAv}*~ zf}`yd#EN!vA_Dn|5Ds{_NbC0`Lf1R(hJ05-={?~xvM6n`j1GQO2HTm_#Psz%h*ae= z2=uqHgwS2i_oOaNWb{?hzL_#IC~9hcPrxH}2LT%1gZA4z;)DrGex<|M<$jW67;WBZSip#kDH5@Jvalw7_UJx_tX z&4N4#GGv1=U8+-{q)F+RH-c*h8n_NRqx&sP=%bbEz>}}FglJv|bLg6Tn9xH(Z)9Mdy&iJa{1HLWdWgZLMj_D! z?0*jPHh{wqUK8HQA2P7wS^y3wVmP;rz-Ko=2n1b(;B15tmwzHemb9!E+O!eMiu^_p zHLGA9R~Ew51f`zGa05ISO@n$AsDU)}Fom2o zFb!*M=JTj+(u5VQB?}KxHbb$_EP@>03{%r%1wz2vSXyYujlMRC8Xzk=HdJ!4lt1-F z4S(~|{4KD6x{(G`sHCO{^3+sTnRqpH3wV{yXLycOf<8k?A#ZzGHd4SNLG@s- z7=(p7GhitZ?t&2>8sZ~sKnAh5Q^Y)S9zg^Y{bW^8Stb~1htUSB^kzbeIE^QS{0vzo z(zh3F#qBhS!0%^6MBv63HY%qOq-QIP|2{#4NM0^0je@s9&7wm^kg9DkdYp`85HsSL ze->E23?mFK9aIOR155dus0PDxV6zazmo`E!^?Z?)Mcgh~8LVeUb;L6~Q*uMMdpoFf z!H~nKyxtBy`&}wyTN+*34&n962L0Hz1a{jY%O!WCWA})~XwN1h5Vr?{@NcV4HU~=i zzJ>5?@}X_qav){)ZWTc?av+Go*$kpW26!0+s-t!?uoQAd(35xU5kX>$WML-=frEDY zMc_6BQ+)$kkOL#`$Q^J;;#nZVMLWREwo@XA_YKI!?>oS;#B<^>-6^>!dMEf2R7QAv zcS2Wgs31hoP8b_=FB4+k1L%8yC-wE9<-0(u3bqPyh>Lc?t?Pk1455q$=ECqZqk%zS zU5Jr`up@{S>T}^1KkzX_sH2Iy!Erw92MXEhs2~NR-Pg)69DWgN6D8Ov6cyFL(>WK7 z-2-kNe<#jULi_jNo4{@n_zxw=K}vZLUEA*jp06t>jRNwZPjY^XASd(q-qh0`22ntz z%Ajhq7gSeKDD*f~2UKCOR|hy9!!|M^aLZm8mGk5o1ajEBFNisYa-zdfy9y&Ejdt&Y zW!!cR5oE3@6aX2^MQZz@mU4W;duk!aLw_>>UWj3JT>>B75BmQZ5aRECsKg>ehTx*5 z2cS93Oc_KL)g6E#{pDa0=tVLb?zSGy5j{Xuw^v-TilRLW=uai-eF5u!Xu zP6N3df;jB;Vh}b;I|P|EU=l&v55bsl+>a0|Bjt3F92`6$8y1_R#e&j0jYx5iz->+0 zVW?C^FoSqdOW?5u-2_KqwX6!yCooZegg;th8`^r9Z;ITG!irCisP~o}Z0enW z=6F#of^bhl1Pw1Rh$h}3=AykP!MFq*Xl7KW74l)5Fdy#TxP`zwd0Cw2K~1kA$fZL5 z7)tIoL&&3!W;qt#D-_1e^AzZ>s-p#RKFGnNuv6gli2GuI9Qt_*dau!wK2#MuW=82W z^#L4IRs<66&uIWDo(3cPUlC&Ycj%h1&&x#-Jz~KxZ^r_DlwlW%=}!q3oH1Zl&-Q1) zHQz6o$460TAcso66Ji6K1$)3}z=KJ@38G#MgT|*GLX;Q7O>kT>H0D7H?JtH^MX(J1 z)42(m=i?u>0K& zOO6s)2;C}yX~j_wg`R_TpYb`U@8W@&2&Ildmp%s)NzULUJUN4;fi8`aq32;Ve>IE{ z7rj`*Es_i8p`tmi*e=`!orl>wcO)U=rh->9O2Nb;xXr-qF*89cGX#P;HH;-Xavg^U z#-$KU&&l{(8%?Y8nR>1{uHg`HrL6`BE!w|Aa zZy8jfa~zarS`I#P;Dq`W5Nu5bx8lmdt$_;&@_jXnBl0xo>3T8Wtd|fexr^}FcF0mf zus4CqG%v6%$P|;F4+nN|DFqjy$6QM#M9)QVR2rTWV9w(lmI`vK2i5oraI1JdflpL` z%&{~=tlZ0j*_C-HXH*G-f$$&!>suXU3HLIV11tf1Jr$4~Gb>>)3U+O6;joH(C4{j1 zEQ^I^IP^UOGPndL{yR)ebYEe?L#s=WLGkc_02`$d&x|BA{sf%?iMWp#3WRzY&;??egnDg7kst^ZHB(TMU{Pjyr+WVb|fc0+{eY4wl zn|2k-{n1SXY9-kkOa-NpoD5q@JqJ3iGcOs?FW~<^= zpBZ)L7ePXn+NFm?rgpfr&8f^M0mKo&>cQ)4{ zHH@@DmA*T2xDKkP;U4EY9B}A>yBMr>^E!0mFu0WgCNiplz|?6GVnq$iZQHa7@uUV? z>$e_qzXxJAH$bcaUWUO$^9}6Z4H&I7%@|}Tm1s!_*IO_~Io*U|DZo|)*?JRt49`IX zX}<}h0LzI%;4a>o5OGu3GAQpBq||PA2GKp>=L2_e?iLz|^8BScd@v{~{RhF~L?2ABq? zr4b~f81g2&0VblSSt7`X25{iTPJ+1Jg>~4)eGFS5a-Uvv7rZ!fi12#uLguW=$3!$` z16#w_VVQO99(3a_IG%usf%jpZn+dlVm`J)0PIKU%0uwE_p#wl$m{FrD3DR|+%|`kS z;2*tit+_AOL^^QCf%QO&-Wi04Ak_qEeE=Er;3h*zq2o;;LvPMaeF*O6))U^mmuxM1 zqkwF|6l0#_1BS;!Bi6v7B=SV@5%8`*BfOoRY!y`L0BJKD!$vJa_z_g}6WnoNx4u7u zif)Ia37ClZNd^j7P(KERdu;?h@fg-p{vCu+cmlzA`H2woSn`S}Tc58&O5gAVv~s@@ zUd0oztPVFH*m50DUKZ&-h4voYD}pGg$a6@A1sd{PcoC!TIPH9Rl&owh4~t){I9@|u z_=G8+Cnok+=ARfBxjf^WN$ydkArq8rAP>vRVNmanfU}1O;mk*TGi2{vDU{y~w=d&mkndY)wM>D60@7)LOur<@AUyP} z1q^L%fpD6z8JL6aw!p(EOBf-As`ALJ6^xd_@CZnb8Q4l`1zXmz(L(^CsV}WyY6lFQ z1mz%y=U^!h7GMOBM_ZnQp+m5v0|0vT96Cs|At6pVD!^?Xp1bKYIe{<0)E0BX%Xk4z z+725vSPKMY(EArK*>c=P5Vx0*F-D^a;yp)!gATofrS#)5A_%wZc(Ucd+ zAbgQ(S-gRAU14MAEx$jCegi?wnnj39m{5)&#D@e0WxV;wMGkL4;XUm8yoK2+E}F2% zuT)S%t#6^=64?5|rZQ7N!Sx*=oCO5g@(#x7{jddu*(=t9U-Z&Vy$$TyE=IO(u#dd) z2xbe=-ZmKD^k7d!NXVd{Z4mL!6Cy~>B``7fJ(RGzNCcj7ML`|i!LZa>29`#=c4+4| z*xh&w-Lm!-WX$|_sGk;$H4IXNkw38CAw;y1%?Gg4b&o;hQOXCfqxqH~w?4pZ`5ZE@)$(8iNd`M!_it%+|Jn zVkY#0wwVJ*G;5OkV*ws={mAE_U?c-Csi@I0sl2SWIK;(Jk}hcFxty7mbstRYSeqJXSFLsVIwDD*QV)jedFU!b@ha|mzw7Z`HaMll2%g{tZgM? z2+!mzOg%2~$lx2CiPqi7;i4*8*cdtT6^t!}n+goS{|b%fnurO1ssoNC;L32TnOa9%+u!$U5=!2Gv-29ZN`0{h5Y3!qIbWcixpIeARFpA znyBIrgm&j$vCwv25|O%d7Yu`x86|Oq!c{Bx|b3!N8T5UzqvEnHU)E|v;*Zn1YaU=8G$3UWEg!t+DlOh70G~IgK;$QMMf}+nl*vG9u%y|#qVkh z2Z@EU*vAl>mAFU|j(y64-lI?&$X^Vy^q@LW4#dJ|)2P236t#K|eSJ(0+9@iQz8;#Y zDBNnuStAyh_60Qm;u=L|+$CW@V<`>nVSypz1p2y*1=Sw5g1+uy3*?a(TQH1Tlhg+& zpi^vt19dN@4{)WftnRy(M|*P=714Zou>ExHKlGBkz?FKxz7JrdFYd6J=coX6VQ0~3 zi~=(nvBAWzg=tZ$AXA}^j zi;C*VwFfegP6$gyD0%BKnpLC-84;lf34Eon4{)SDo}sU;YZRrCtP+Go?d(4wL`mRA z1();z@+7xu%g1hs72jKmJ}L>OQ133_?*S;9D{!a!RS=?{D}Y_RN=)=eCdvXEc#W@H z306#tlp(b~-=Xba!Pf?N>1$OLXeZBy^fkN_Acy9u0CVi)e?Ya0U^r#*^dDfT3P8Wc zf54MY=ydJyvOAfZes_!c>(l&C(nlRa|3MWxV|DBQpkvek^?CU}=mCsge*Hh_UyLq( zCx$vvo$ti}7{mWU3(;c)JsLk&hZg$sK}<*%2{fRYSRZM$OG`->#b`iFBz*Y?_{hSs z3;c5cq@m}^DT$5@RbT%}4$_1kbCN=~rqF9?V;eM~hwI8Ph_Q$vJuUEOgDk^?v+aB( zH4%XgSm2%&#*8pDS?xUDM=J5zVzy&}f!U%p@>6=o)a%oRW~+FObswE}@N zB@b^JFA&d$pae^Ug1b3*hJQYN*vRMO8j&X;l0s@yn70N>W8s3S_hC5 zP9n$=9Vo5FRRodJ1;k;52%_kxq$H9Ssk%_mWN#6H3SDSM{v;9P^K2y*;+E+gB`&;0 z-*>~BgxqzZr}@uOQbfsmP#f1kMh#ZD7&$zHAo}`(F;w|XhOL0M=!0t`!U&R?tYnF} z1~4#A4;MlF6QE>Ro^a8+M6tYk79k?_BoPvaK9O;JrI=K|xgt_ME0t8y$^PKer5Fab zCuxnz|qG)AUa2lz?stB3~v}dbV`@yXe@A{x{C-=eFgGM#}M+X*ccQNiV5s_4IKYt z3(+w)YAq^w0t`(9wq6i z;Dd`LOaMKP2qVi9^je+}BE<&!>7@@!iaA!Gd*PV~y0cSB9tC4Kvq=P=-wh>IU^ucx z1m;>pHC>*IAhFial8P@ykj}44aPAD({;f5H_}wdpr-ZC*AZAzJFvtih?;RmpZJ=$R zy(dJ`UueXMworQc2aG@-+X_Zfab1Lf*VN3&@yjPtT+tES>JuZNjJVQV8FbqYntBRH zOse1)BLzo8frq8csEZUba1ij2&q8>EQNtc$sU|Ig#M%p-sKf9g1S7LTz*WMk!pEL( z?4h=gW~bVCv@vbb6>@4&}Fr2<;gLwH>mDt4#mA z0}2@i_Cw)39X0?wXQ~Mf&|%`oFqm?swvux6UEux8XlGb19EEpXurD;S=_pqnH9A9V zwjl_o9|psB6`W5rs@T1i%YvrD_-ua`S>gMl{SgkS z!;$}txN`g*Dd8}H{4)Z>-SchIZszh716APs@dHY}F&+*6gjasI>_P-#$f-b=ybKT}CBCXPc zN!C)?pEi7Q*`N3md){7dnITfI4F;f>HJ^*}k-pnTnTrpVfQU~vwXa2h1FR%!0~0^=pNYT9er*v7>sn$UsRgrc5KFKAYib>0zfK)|U6e@a>0u?Fpu1 z5QPNZhN87YU5ur9CUgV9=Rgb?%(_E;DVxm0wY3v^(9A~$4vP<>?Rzq*IEY-FEDMOV zP|?L9WpNl(`95N$lYK$y3GL%Atc}pC&yV-&!s;=maL3Q5&i_ z#eTVOxd>2q$zFbR@D&%ei$8RPfdY&)UP>Kio!4garfPxMCfT-77QEVw4HZHp{S)x? zmW=lkNOF8hG*tS4;ayl)48JrtymYqfvF}y@ROX;lq#rblO@^787Qy~$k{vHMx`H}r z=N}w;t#l9ce=>%8)rPl}@G!eGn1vses|TL2xP;@+A{2Z029z&1$6P6nFfg?a6PZTE zR6ZnJWKWkB>=S%dW7%Srb~hM7$vE@M1I5&eCVKxMD%BkU3gGhDwad{G?d<9ky(0+- z|9QzqDRH4sGwDm$Y#omDqg9fv!aOSp7AwaT7t3@tgkvMhS0kv5*%L z^NeRSa(ZSzu&DN&=j9!Q`=jC>*%(J@(5wVy{>ejdi7Q@)lCBMbdA==6NC_`i21v^0 zbGX<7Hhi^FkW`MK$;9;pY*)% zefI7nGL+v)E4e`#yZE{%_Sa*q>==&0ZK+y(}S(XBe!m9Eb{LQ__^o%2k)jY_s`x5)pGk|L5bNleK)mp56&Pi zOtG#LD{YWty_cy0lX6{S->deMXN-<`$54BV(*Ho|sd9V>T?ZXkloo&O3xSGSp11)z zevv#*(RG%|UskiQqooRoEethufS}{tjXhufNrPgq_vG|_eI{es$QEVO9?`(D^<;-; zDzZdzr?NP$d|9cxZ*}8gXD(VBMXgwyCm~P}5H)a#svDI5Oh!zdodh7HR!;%28lOyKq5iCkwiNr*vfi>J zs#szC54*$v!|shAtSSVb;OWl(L{@&~%)#dLL`}D>?J&B}Q zqJO4XW?lRp(aIV7``<-dvLw2+z$faJBEtXkk~~m}zY-lvm4JrM3oO`zPV-hMy4rHT ztn>pKn%6!MiVO4(LM6sU@PRlM;fT|+7Qb(DjwSJYctsI5VV1$BAbxoFOfwj*J&pvK zEK~1y?lZ%Czq$kTeSzJ5w>&{(ItB_k^j#Va&E#?dw}kNHYT=(D|`c z{A*U;Ojv7M75ApBksC%1p}dKaygY~HPOmZbP2Q$-%bdk)@2iQQ;Ih&L!3yd|5;uwpb4ETF`Ulu? zwgwbHj*Ou9>EYmmKVH zkE`tZKN=o4&;@MGLgKlqa?4)i%MOO*{#7;{2>3s0ASK>25o8Ak0fB)D0l}3hYDo46 zF1e)$iLd4GKz(n*A)HsQZ12MXU|518Hoe}2n#VGeah)FK??OgfA!D8m6l1cME@;i^KrT)gokIT~AHZxVr4a*huS*y9n zXS}yF?UPx&ZqFyjB>u>|RK9d#eGXU`!-9%3bzr9~poK9t%qC%ftK??rCHzB87*!VL zT-ejv0Tijg=r?gvfyr;=kip0B>FN3Tc=&=zMBbO zjaftgI`eQ0lZ8>Ac+Jf6D*28%+-9iiORBiHqy(XV?}0G(RYe$!`Z8!m%sU%l2mPuf z3|{{k7q}0k*sTilixM7rXoY#!8JvoGL)hQJxKhW+jsm7$AH#G}@4@c_hac`?d_Rzl zKjgB%27ckic(E+R?i0W=!oEVnV7t9ag%moN<*17KiEX$t?iRQAtIJ7Ramv*_RNQ=h zT$w-@m8ikenq1O)zK)2S&9;=hrbh8{!)yOF4Ctt+<5YwkB_TL3ORq?ux#WoI^Szn@ zio9EJsOrpb-p+PB!^42wPhpwb5S8CjP(5lAJ4!|u$uE6)P~)I1wgAT-Pm3bjAtr@` z`ASZ-m2-tmxd?%Iw8%2U74e6O;K;`zTSgLXI<2hbaVgfI$n_*Lz-Gf}r6fNIXZ2k@ z05~wmYtU>lOm}41GJ+#A(d1#E+^+YS=2WSbYs>1)pAz0)HCgVh>1yLAB0s)_ByU-9 zn9$tJJ25%S+ny0`4Y%mA0px6nDn|?@X*Ml< z&h0bP(bnB!Ehbu_z)!3yi=R4}Z&@wYV!|OHtdO>vQE@E=7Eh>94(F%?8pe z;IlUSa$%No6nrNGuRH{=JwykqZjMhfGbj!}!D%40vYtFfXaHg;J2fe3O`{awcV$)M zTu=2Zi=+Npox2ERhSF~bND)OD6 ze8vD41XpO)M$M*dPHT{KxG!xd_W&F8s`(NWqNFV;`Mm7~a1veM8fSqgxGC82_I8f6 zcV5*Rz=oqAtGk(be2Ms%%EO_d z>7LoPmj>mY#gC-x-{?!CsAuRisMC)=TNX&Uaa@%-R{U(|kB>kdC8woZ)-8FGA=+B+ z-@v=;JeA#if7K-iyofye^#+_JF}yk2uA4ud;42!JFHlf8v8A)A_GqG5lYud%WQJ{i zr<;x2+&mEpt6t-H(3stMSS&Q_M#y$^QD%kfQ5z7pu(3sK?I+QVZvQBAD)IiM%_*^< zdTAK%39`hq$?s55wA*v>w$+wOdaL(~lNC?!Myl=}3C(%3v|#Ld3Ka1EyL(U6ok&-! zgXxrl(hS-L-;Yy(fns&H*c(psEXfamiSVM`>}Y*UZ(-{%_sP<`-p_ZQx!d3cem^qJr60M)S!C$=Z3*aYQ|~h#C=h&~gGihV zC7tI9)Lf0_ykpiv3h4^vDv0F*Ga+&)_F2=oBz`SHXiv|Y{tzsHSQNQA(rSX`@vRo{ z41^y>a9LA9#@Krh>qRj{*XeymZ|^W=P+;Qpd3CC~@mhG#mFNO=L(m^)GW#y@wF%nS z61^)rctdVgX_t8=uof}UE6zn4fgi!wgYhBbgEt<6SMsdfuKmPrOFiOGdd=0Jyk}J4 z3(WrDV#RH&K_iku&$zn6V0csKvc7Hn!3#?8Hs()^pCtrm+Ci%?6r0BVQ^DQEuush& zenKFiCC$pN263(e#YN9dF^QSL@TQ%1bz7niXb3)XVVEtgu!KlvPcp08V#20yM;K^k zv9R?)6z>^Csm{<%Q>i!}n1u9XzumUQNJS>pe<4cBT2Z$nE(lIiE%Ff(KkTX6N@kmZRy*v;S_X=O3zbZE7?qewRn{RRnOov*I<7>8iude8~JvKA0 z@!k`0U%`-Gz`gzIYkc|EBAcRjuqjK`Q(bPK9!r(U|?o%E0S+$FKa+5LYKiV4&?8v(q4KPBgqFuKB;=WvTKoZ?9&X9 z?#RXPinDw@2>No&$~ySUxfmsPQQ;@;7<+54gkrds9>nz z9=4zW&qNZO?^Dz;*FaN_f3(XJH^$-s!Eub3o;6ULP? zB5mu@z>{{>o_d?&(0Q9UO{e-$scULPr>n@YwT8lwb;#n(*h5!@ZJYEko`%9mx7lr8 z-ELgelg8wr5sWeRoj(j3{AZoMpg@1wzEsQi7+UXffDh(u#A>W)K9=vb>qTanaFAdW z%i9b_Pg3Rz&1i{n<%m^h=?y+<^l4*fsa&N6j^JczTm=W#(s`@(sUzlST}1`f(mr$q zTI2YN_qieFXkRG;m`A-;``e<4Ft%95IF}SZ7bpg55yle!j7ZCo!AC$aH`B7OG?h;? zwqC3516mXeHDM{$4WYsji8~wDnQRy2IdbYN%|gN2S0q+@Tr>o3n$mBZwaBIMzi)*@ zu5m%&9ie2O(&NkeV$)z4yTS!M#!5awiAaC8=&0@-0|;N|@uF0y+Q|1h?JF`L4z$0M zSi}g0#toiaZo8mx6z|7bV@ck&QiyGZ6_0To2I|wp{?_nHhU$tk%&*!Rt_$S}afCE$ z6r|1}IQfgWr;}~2n^Ay^ zfTiAtHFa~~G%W+MrLr4gb9mwAgBCz1yQ6%jk}^A#jQD~m!*mKkiq`1dfa8zPp-ARf zqYo(?D9rUlC+3x42Ld%_$$$jWC3LndL;y3p1^s@EVk1E)u{P@G;sOAZ(_k}sRFdR% zTgOsda?`*toqAi5i+zpBZ%0~t%v*8*DCIC;2hgWb7*(qy*bb)$ykRWIukZ$K-m{VJ zYogSGJrI%y4q4^6CnZ?yzG0~I*zwqRQ8KQ$5Y?FBYR|PxEQUQSD8b5E_(~6WU4w#$ z-kftI!+ezov>X<${GLUI(Kw&sg;TCeKY8AlDzl=F7J@iL;>lI$>@UI+V&Y0YKNDa3AEU>p?&T4Pnzhk!MzaaatQ608s z2J)E0B6y8{lSwn|t{*dAsAB^j7_ZD87#nG?)bY~$LZ|as zJxk~k;JHq&TL?DJEMBytQc~*|^rJYue%Q2ghn>T2aHMt1=#4haW#( ztX5Nm4VTIByshLp)}{JgblQ@_S17`Bt2n%U2<9w8p!0B45mHyR7_5M+m5z;t19h#= zyBm7;Uj3{CjvLw%9!4AWjO1dD$u8HtD$UnQ1D-8W&>T@keD>DlTk$M{Sc?|CQqiI3+FicUn(*SCRG z!hC}AI6-R!9$G^T6Bj`3v>$cKV=(EV{muTv4%XISBwneJwTI0{p|9!UGYQ}pkT($h z(GofId!jbqjq}H0yd^>s9yH|kBQ}xk71flFY)o~p`s)2rrcIrSOr`-CvanvBX`*PO znv)LO7z#~|KIC1fnT%U8(BgZ|C6~$f3?oGZTXVVy0Uc+U%k@AiGE#D4*H8)82}8bh z)ikIifOGvco3E-F3rmKqvdckdqtTnp5p1=rgXZ0kk4dDPIN9VA7p+v-SU~>!i=-~k z>Nq{F4EaEHfHftTK38djVmu=F1TqbsW{gcf2E|RrscEvUG3(ond;9frP3K5F|N-?u&~eejQ={Nx#b* z(i$>^79nWo6RgR+$sANrJ0ZXLo$aU#`;nBJDQ@S?ya5p4$H`Rq_RIdWAkZ7?)AN4P z_gA{(yb0?V{9A+Z6I{&g!tq}h?je=CaA{7H zo00aHi3J0duf)7GZ>K&a&(1q*2?Ea|8)-QTZ0I$Ab+CZ(Bg$RGL|LgyTwcG7i#fDu=u;>`%BP0)x- zC}A&<&MFTAjjf0u|43{zlxq;bLzd@@=U{m~AtFOpXeqK4->jJ>x#&ceJEp)i1uuX5 z{z%#aO=7+JFjKkrbHbW4MgqBctAaWu;Bx=_(yDlR0piiE;zL4d9}p3j-^z4L zFMlfPBaaS5c9*2yKy8DgyO3l>Z9qpQ?X{R3c_|x&Vn`u}2jfHiL>FHfpb(r~{9(pz zLTve6N_CPg!&tc-5x^t8(%&hEr@hXZn?w)O!nX5x{Oc{nnOP0SG9yF8RkoTLtwtwNh9|4RIGH0poG!k|=EHDp8<{UfZ9CsZH zP+vY-JuL|D?7&<>3*8nHntzY$8}nG52}RC1WCs!`ft%1~!o9bZ7w~*}_CrZ@g?)J@ za4N!FV|X#J-g9CkzP}|a;W;HM;myHP-Q^)K7@b2`-SggtTZo02epJCV4KI6`i_%px zM0ZskjP!j>2uqdh>MyO0@Kzk86!O~&o$&7ppcm>o8PG?zcaw5en_+h!1Er&Bjwg2L zwgANvt(YuqPbUMQw&27|Se?!!(N1bA=MCH{ z5*CJuG*cUcE8ZQwrAUFFKVcT*%K0<7DuzBfRjAN13owc|vX{%@wab7~4k>vK3uG1H^g+*lmILy zl!T=Wi1q4v1kv= zByv1q)Y?&tNlBu{wX6ZU|;n&PR$PttS>=<;&iDXI^#xS^76C!@ujCkiA z5v+A1rN=fkSqN#Qh1ylmU2htA6ZK~NFK1R~< z3RNGLwKrFzQw~Xk{LnsH*`))2mYUiDOUoUPI3wyx4L!ZI8Pu7Np7;(z;0pXHP9^CJ zap^L)T=o|?*Y~?FYiwgT+7d1^NG$o3bTgL}5Ldn5NH<~E<3*9W#oZT>W~CkrYhYKI z#k)D!wjCV=G=>H=1=NPV(*4wq$6OmW*Ay@sa>0SC=#arF)U@cTo#z2UFBgYX1$4yS&{?k}cfpRdI`ZN-(&gb5H)46)oc|MvnEo# zmS@hTV$bz04dqWa@c-9OX@$o+g}T5tvl?4{k3f9(;eGe>|Kj&QH14n%1^b7zpVnni{)xuq zlIW`#K|(-aC8}&F0WXyoRImkOJ?*s-gX#l5yoxP4(s;1VS|CAUg^xi}!6XbR8`3rw z*^lXu>`;eS=gP&cxQhMwtY+gAh=d zk)uqE@a0F!L`CIUj85^fbmrr69^|Bzb^}3dK^;Ux!~=GMz&*ywjkWtv)Ga^T?T2y} zjC5!ibp`CCSl2#WJ;2_hp$R%U@;F`=UbY)4I&{{zYMaU|6|i_d&+a3SW!EhnCh2TN zi9tGgdNqG-bYida>wqagh{tm8Mjhz%1#{h$H`~NkD6Et}PC0d+TsxKm!a9m)mxTtD zzWVRJ=hfN`1~N{>w3D>Zh3LmkFOshycoJP84SlU5z|rhJ58N?jeAVkbe8@9)aWidCy24I=@TZD{}4zT#P164u6grofFQ+Q0srj?&WPRc@u zBF(E|luFgxFJ_FV^>k_H5()CX(sk0YEg^!<{U(31QoC5l-6<>J&~Elo;FpYMl44JM z3-BB21tc*aux?UjCb5P*EVQj0r?P(VijLBI1`Pr<`bgRadz6<2tikVy$9bm0t43AG zKw@P$j>jd+@dB?it|+mRCuzx9)U($~XP-zz7sGTmg!8!AGCm@{K+~S!SGdC#n^P6B zQ)GjS+~?PoZ<2_&mO$$Rd0R4fEEe1ef<@<8b^Aba7MWC#yd(XchtUZ80VVD$Y{O>6;+j6P#!f!Cr!zQ|9{XRwB#`~R^D%w{T+YZGb+j&{FMIgB6Y6$OrHMA%ZsDqTIZd2li=_u;?1x^!a~-~Bvz0<=CGwi9JUD^2mwq@ zxrqz(mjgwd@K~|XlSlI+cu`EUOK2->+-U>&h7BTGkY2`iFp+T* z({r5m(r${^o6rOPYj^lsZZY;{oV6AmIkhPUhCkZ1WJ|4&G*@VOgmfqNE=ugRDmOJf zO4a7h3QC=@x-6O52L&&VE3@#zqY!>YnWq93%wMXfE5DwsB9Esyx^bJ^=8U{as-nR! z!p?j{;8Qyrf691$EZ0Jz%jYzUQ*;hm?x(*st0Sm|ALr-PJ|--oX=#kVSj=gurR9kY z4usjX#OKr6ax!0bQc;RY^+kw8OcBWtBvWhV*idOyinhS1+RX{n+_c7jWuIuVP4WZ6 zpba)9zm@CviC4*v(u|rJ_JaZy1rq9tcUh&@-QJobk>#z?N*z~avP@4kvWqpd1*UxM zs`~su_1BxK>^EQS*M~ngztIYGk6_>jHR(H~B3NvoeZU?` z-U0l1R+%_2yv#^kumXkH$GC%F9p(;rD%G4eIHhx|E(2&kFX;O zo;KZnd(ZYr5D+qnc)oialE`>0#|Pk8j-x}xmy zuQaw|O?~wR74%mn<|0P07W6eDotb_dgl61Rv54e^q>J}ei0r}wxY{m4b$de1#+L`~;x&Lw2>+_Fu{x8(4G5Jt0s!jW*&`_)bVq#)! zAQrWLUi`kex>!nNBw*zrOW+*Ma9oV)&jp%cR#I?!uq>zqFu>Nu3o;>VpFkg9g_)jB zVQ2WNN_*ITt2dQ-5Ps~S$myjyf__;#9oOpIhJ4GrF_#>n&+&dmJtC&W+kmlnp>RLK z{Ma#8YvDj?nRVRqf+oX|u3W26vt_JX_qqg7z;y39o`nY=4Gez-Y|s%rj`K&S3J$d3 zA8=0WDGh5FrmD|wN>Xx?h?Ilx-e9D0^gRVMeL8DWUbJk~kXZ)|i%r{}x^`ptQQAGv zA_}iH#og(1Z-|6c&@=(A?&E2YraxZicD8L-b9Pi>@B|Uq*{npxo$$&d%Jn)L9JI^o zqCPQ<{-$+t;11BF1;uYCF&@K}J-Ug>96*n$WodD3(4P^7=S@pWZB9gp$z|yP#u;!B zk6=?U6wLi;Q4IwG%a<$2AsbTVNG$WZ63HA)TdrNdADAyq^r)G7ez!8nfyI?6IW!`=%*=XP7^uimp)w@Eh-2d_rfWtM7-u*t(yy(VNC{5G;GB;2%X{)h-vbLje!#-oQa3#VMAmiBv_+IK$Jy1$WYd3!=9S()>Z3a_ zCvk_69fX%i>XMZVz=d?C1XBCiN=Kx{sM3lSX37<#=eP0uJ3S`N8s^&c#?2CvdipKe zMH{AIN|-!DGio;Fi4DZk=RKb@6xerGp=Bb3VX3&5E41G1pGWI9Ck4;q6R z>vsNA!@A9s6r6vX8IIptruZM)qv7$8fuF+vKgVaJlV4gga?3N_HeVkpzAdf%dQ2=z?&~+nP;0P z>Ax*b>%CHs-`g`xuXt73w~=b%JFq8)In~8(O@J#F%;v%_Py*w=Ih#Xeewm9k#1;w- zd6LDQIZ~z!2efHXJ{(s&h%(Kx8xhtcr|-ek+Vxpxw2tt}Nawa_c1GI7=sYagbRgPt zw@6lfRDxIWgg?Tk`r{|3zIazbttJp@>UXuK4Ff*^O}kI3N?EoI5E3=F%hK`+w5nPjV~xH;d#fQP_ONVqv>bG->6mICHFZ_4Ku zI?p~-1XD`W$n3{rE0)*rrjS00qzxdK7Qt8pu6DDtQi~kGojLLfhH{SB{ z&Tybz{Gg}6CF~-Wg-_)gdhwPxMc(Fek+do(${mt2O`?FZHi2eVJ^>dj?mmx}S#)%w zQOYW&#ud?~ki*yFn>5S$NcasCwgzwPP)ch+k;;J7KB4fHE++5=;y>Z~Rw8fd@f)t% zzu~I!|H9ST!^z$9Sfbd1P>lL1hw75gB9ise z+k8nSD~F2DC8tUVm(6`Lce5oxhcpN{sfQnKfT-IMX|-&3BLFt8+{HGhh@;levCOIb`yT3DnKmR_?-Jcb&zZP~4Pj zV3=t=;kG0Ak`^h}V|TshnE*+-&dg+~pCE_L;bljQz3N$z^n5$U9rUYaUHLrc`*5yO z=nRgy|1htuili*YV`Yf??Dut{d+d6&#f1yatqT(UUj>wczzerOlfVO+?l++`6Dnrh#P2BS~Y0KWA z7(!uN;4(eqHw!}RLRCX?qxwdA^aP=e_i~h6Nx_#%Y*4O!0UH@=(pcE7EjHGdqt#m*jk!fs$05xSUQ>ii+79F#^j(x(fzWA=2)G=^$UmvXflGLX^i#) zVec>{W#GLV*%#)P({0bw=Pqvw@^;}KRLvBrh@nM?oXS4`s5r&x?&=oqfm|I7L?KMX zEpf15u{DQZz_oHX!1}lhN`7bvK^*7>wjgRWO~e`MI zPpDH8t)2Z&D(WmZ-yaoEE=%d5*XzXeD)?fGjejZ}9U1J#h~m|B8QJ^7*Ib+llv?SRYqRg{aZHBkW^f=gSDqeRY3E@LHYF3v5b-OOZ?n5 z%0QUQRuiXMf8kN`aP7K%r6a?G)Wm-kZQxi9en`n0gI9+Gb9dneK4l!U6X7)8&>zHAtUV*sDFRKzwYSpOl(Qb z@2__An|%cT=gScRi#5)b{$Ut#B>PmD-~vc8GP0zKDi!E@UwE3qB7CuUi8seqalq=u z^2?V8nnzr8+HfkNFKCusjr#Qz8CvHh>|Pg}KGWIV*2f$7Gsf>GcS9nKq9|EnG$3Vp zqs+zhun_0z)>%sC_r3)SE)bHC>r!7jXJbrJsz7oTn&S(dzF>y2|Ir9C?psj@cxpRpx+@kL_-mbDH1T8G$muzGOU(Yvj2P> zA+rZ@9OeRefe#ZYAjmtyQDr!Q^U=_4_{9&*I>~K3l){1*Bu4~{+K>drbUCMmW=a*q zRvl&ca{lUwi##|i8iU#&opr$qLd>yg1AQlO%8NBER>esO(lg^bY%s+W^jqNF`!(9W zf5s!U!V+7GjD+&VV5Fg~6C5E|Ozf1o$?OOkdOHP%gZz zgFRkYz|rePx0KVK#W^eJ7bLe%AsMf$T&_;|(=T&y<`Z6liA{0q{$rbXt2(oxGwWmG9x0IG(S@peb`_GU2Z6wO?lg=n zy$f~W*yKdLDT`D}{TaFXgxSW&4YfFe-hygWgS;_Y;T)NWnsgmKT3kgeho|EN^DMtK zcJ?WrtOVJ0tHh9Tua9L3KH`0Q8JKhGqqF=jcDAOwpTrHecICHM2+kJ-BF($3VCn>g zZ15N;+%)(~`g9Hf8G6E&vgz?r!NK z>f!F}^j}=0>8Oq^jqVR>4Y7oggtEh)L+|2;ugs&s@Ddn5O0q`r^I2?zuhnIggiuymXGc!X_KAPa#d(g;?ax{u#AdHD*R+WzyxW5n zd}(yrK-V1b$Psa+pOX;RYU-#X1m@Oa4irro)Mjgru%q`dJxuep)n#IsO^ac(#YNiW zLsXCmB_z@k55lIv)}m}id#3EdRMMudLD$y@i#(A6Ry# zI{ju1>2W{DJn~IhENY2((aKN{vaGycSx(efxFKITVBex@TN zWi(%EqaEl_Xj=1%@>@$$g3;lUb2`!h`8TEEzAiES6ppp>grPl5T+{gghOqS%C}qq}vjK{p$kyOfQR? zA(M+17)xTx*Td*l9K`I}*KY`CY_i!0J}?c@?j^zKM9tLD`s11o&0nIj1&v z>eCqHql2S!nX-(Fl!pfMYbcEyv${axSL|U8YSGwiA8!`7#U)Y_zmjrn(cR*cbES@s z+b%euS2nSVaGb`ao5wojy}%%!{_b1SRzDglkQgi-pr5-V1Br8Zd~uuNxpA>5wzcYS zjA@4V{WIn!kL5jnG1T8nKzA3X+H^ z)>+j$10job8;44(;S{2uk=&}OrZo|~M>@v*7fWI-i=Vr|P|khEahvTDQUD&spUOkwa%4WmJ~7Skj80 ziSgs~$g%Hx^TCoB4hbIeCR#n1m z^O!4{#4V@yJ68nxCJQ48dLR{x64T;Y(78ju0iea1O$qjh{%tw_+Wvpe1x1bk@c&h* z5_=Z=_au?@!W;5$G^2RN*WkB_+5KIRC-BF_B=(-cB`#hO0sn-eqgX}IfuyIfa@oCu zQRv745{+T9@fO$W+7k@!enozVmkIGw9HbG!JFS*{$tZi^RTfq%Mb!*fYo=wU8$E4A?xqPGya|Ab|0BMPfTvp#<(?zH#X` zPV^IPD(-VoH?WC^;3MX9^{}{s&c=W-_LgnT#pX60F4JSbBeR*4>?!N=k4Mb6^r6$xsDH9b#0;cBb zS#9kR@+38eH`xC~D(kKMA0RIH%U3r31|q@lu$t^&AlBWY|A&*R;jHd%YHt6(v4MYl zpoNqgLtK@(z%m+mH6e?>8%`|+Z{px&S|4Pz zy-cJY^?f?H)w%;&`8K7o^6?_(q%EgoAHQPcha4AwXC9x{+>OS{LNxcLDoUl=TqUKp zA#*a<4@98p#~{2aM%HfNDD`4;McT^&7`6oxHmS>$Vm8G3>JyN17ZlBSy&) z3ohZ^b51 zxn;~h8v`rpze%J9^TOQf#MPCVAn;;pTtWCDrquVdxD5+NLQ@C;u^%)=zfytY13d(^ z@(`p@+ymEPvLFX&n17w}Z)k`UpC(W3y^_RLgru0B3!?>_79kAC&&}6oo0*MrR&(`y zBW@$EZIf_?l%uTkR-zHVWV$Dy%(on7&f`$e(EQ=v;Z{VkG!ss`Ay%SK8rF8C$5_=L zpg7d!vMle5DE+w|IQc7XuRYz7SF|IpA@l$YapBsxGX&N5#s zMEQn`$%}+czgQiJ-$}5agQL)+-~yp25E9~Kim+@WT1fymMoeHSbO}D}3OG?TzE6)d zQT_zQ=uhFK2rKj0Ga}eq6fa~qz+YfBS z$NG+X>tRJe`h67}J^xdo__uTrc#HS95-1?5C*kqJRo!5VV*I@(DVG}I)2Hu)_6QtWquspM-Xt{jqD;uzxpZmJ>ciSXgUYqOzu#j5@rj+c}Sm16u#%e zY@(Dkvn#O9_xMrWF1-LPKC)freb?LxsMbsMl0^i;mCJUuZ%?1*!%#!a zyc4)IBx~+LowJa*KkkvcW;_et?}dGDS}z4g@ErtMbgx)^ z5^)uU#zfW^0$7KcEF7pB3wyXImZB~4SVFi^Ub3TGlWno_8^(+)w7|GV;-TCuSrM_-H zATB=yPSU1~0!l{{CbIjUv+9yYjU-dfEb)Vx(Zvz8>p+_0U#KV;l5{DZRW9AdBD-oV z39WT<5_QMy>=*TnK8#Mo*G$2Ce)~p{8RRBw=J#&Ys`tAD-#adW8EWe&i?HcJ~s5wciv=U7odyanI1d)ZB>%RY#qZajo!S6X*FN7jr1 zm$p|oi{I~Q+h_Xj{NmS-rx9g{1#d!eZmGhy&?i;_5weI-?;?;ntH3Z8j4}=dPSN67 z+h-r#A-66Smi)e1mNDS$R}20Y11osS-`SSnC>j^g1>**oKUpoO)5q$oOwLzE)AS*~ zh32KUBjgG54fEAi%!_!{YgEUT#Nm8&i@JN9>VLbhPRUOf>s45Ot)b20$^~ zqo=D9DW)$+xf6BXL1f70j14>VMV#)E^`l#gD@>`H>%J38nm5~c$~Otplo@K}f{iN* zmfwW;J}xj^8~#po6(~GnD9=cfEzvvqCEerN4u7K8Zi=uz%-^4n()5#L(8j1+{Dhvt zqq;gt*yE4_)JEf0>hD4jDP)2ZGV=W*%B4uwI^%a$#egt$pWoD157J^9R*B36zOsEa)_n?sF=t}3EjPcJ*etVNY*Z`kDHkf61xn)>P85&Cg2Zcjr@*->0egyX}DvGX3 zlLs-769V2)J(ZXp!?0SOrcpPk7K0$}%)dC`2Sp#SNmjON;5g#JYhnnAS4E7%tfToB z!W?Ot6u=z|^^oC{A;zI*BMyaIg^g2(eULqTODM4`@`BuQHS3YjfA@4u@MMuK=n3-A zEh|KPLDqW^rSH#o_E5GSSU{hX#Kos-P<s>yaP_{?`r> zdrI+|=JyUU`*&gXt9au7Ve32Kss8@|bM3vyy>{8VjI2l@tBkaaw2%=+LgJ>K%*0Wd z4T_3NG8(pIuT(_JNOmb2>i>G*x9;cq{{B54@7(9}^*XQfI_JF3c%S!L_{|29{05KY zb+y%Wr&#>Xi7J`yUMnPQSD{eMV0OZ8s7FIfL;rHDrnqYOSIt>^xC9+qt|a+;neodn zef5>wjWTyR1eN}peL9yqYS0ju(f^EIq$Ysr>>;(7ovAJF32NDGXCu;wMAY2lYuver z?_*4cRk$Qx?h@J7E>fWoNZ!lwkz>;%MCf#{;tOieBle$g!(5=NrVH8 z-6&4^rXW$}t+K>QamJz7eHX=xpWI8Zd^&K3@Z$vAtGiak!%SI4uLyPR?P@X69C6N( zPWErv9!)&C6ghOuq5k`}^*)=PCf6vH+=_BauD3iBQ(QFi?D|X9w#igi@;$}NS)FD> zmTo0^(sgGv1tk1lbiMcycr7ZIPdA`;X!@Qp1C!h9`~&=HpH^vjeUS4b79ZHd*1SfA@am|Jwu)8>T1LEE8E|vEw5T$r5U@k(lv54 zT=IN*wUIZ=?BvC#~#l3|BT2)o*Z*%$%}t`_gJK8 z_yReMzDuby&@$qf|7AjxX1c@R(A&O8&YxCA`MXT`3Jj9O-F@~xeSgoNCn3PMKS5%R z!Ue021DChBk9PZid;?G5{LpeD427=Re<%O%dP$)VxA%>Hme|awU;q1#>&3744wLt# z&xtkJZi|?k{5{4#+&y}VkBcri`-a<(xsp; zvF%Pt3|xXiHK9MM<7DN3RMZfUs!KBcy~y+XrL^HXH*XH%aa?Pwd>VFQ7-ms6y&A{hj!80;RW> zw?^swoXZp+sdqHq^3J}oOTgCr^Z9hg6V+j)4^uuL_6E(&%B^ZMeE8(_$sXU#o0}e~ zZCLLdq+9spLSd8e3|)8?e~gn|C$mT}jJI zIpS&l&gqw2^q{;9f5w>2hLc{pUN;l+-&VT^XbWtXh*HdH>s@2!R;4)EbNSY8Px8`r zhIyP+AK^Vr3T#+++DN{8sRz0e&zZl{(ms^|8oUC7Qu4C)J668fv8ky5&DHgcC2PxFW*cV@|8=vqJrc3-XNJFAOJ{v? ztbqx~UYS$&(Tpo&%L0zrUOCTG%9A9$k{DooiaA82T1Knnm&FxDvX?|dVettsMq3er zwMW}wL_Egd=E_7~H>kVb^R3F4rU2=N3Gp>P3G%5zXZ$8U7b$jY=kzySb^i{P1CGQ;lS7;X|B-h&%L|`l|vUeq<5UV z?K~{+;5T<<^{hk84gFqn6UznR)0YGH-ATN0P`)K_=a7GW60dvDd&|vd=2Gcwo^@~s z3GOx(XuOqDlX@alkbS#j!Ho}!$y@I1T3eH=<#X=Vrz8(?R>l@b!wn85RyFKT9A~U* zpCrqvHZk2I`)r$}tNI|QB~sg5-)VF zY-5jS33K|{-%wS#(4*L+lC+P0SiSZ0#IWPF=AEmOvaWu%9%X#y9&l2AFn!>qy4;~Z zjH$V92FmM#?z-5YkWS$-+m@33+-gUrh8yC;I)$LphBcOr{yK*xtt8kj*X~;hgBo+B@a{iHGitrRSv^b^CSt z7{t9!{48I7YP@bO=jB}Ks&8M9NSMq>R!#kSyVlV__`pSu4E+t(-MQoQncbhWjQ^cy z;(O^gQha^O;3~*nm{cB){$-;qyB~k2qZ6n6LP895X4oB3k9RWAt)kpz{Wy`CE(BNO zVxx;^qMW9B(QiGR2`_e15?!`zHFlb+MP57~-Nqi`vW54L?ZqaefW)Futph&^DjQ2X z{n{_Bov2Fo^>HW?xM-(f_uga9BQUYauXxUnWxMqj0XKzb%LHd49V8VBk5pOTUw+Mj zA@uz5D3)8t+2#qn6>#}_vd?$*#*X%g%bK2(KSmlGF9&*jPhaggG z?;fxs@oLJr#{>DbgJE>01>JERwcB-Sdz%{H3<|0Hab`vdr$+b8_e?|_lQe!mD&Dvd zUlQK9aIVDQ@~@SF!7JzZhbKKIa~c<-1%LO(g%xDv{JLC*>eW+vN7gSt{%gisU4ms7 zuf*(!tYs3lD|Y@?IxZ#Q-k86mX0HTU_b-9YFjoG_{KjRfu`$oxGa~8+Ez|!zBiIgb zH?Cx?uEVu&QCmXTy=V&Ph{aiH%P6 zAv3}1f28e#qV%uTZLzkM4RZ{%TRUnar+s}*)|G4zw$9<_!E&mqez&&1axpA#=UyI*F)RYHp-ozrt6clxgHf26`qcE^nb~w$G(2zd%?x{^Nxo15~AD_rPEGl zO&k4Ld=kyl#&ws!3*A_FQau zgqM`;wI&{tWt367*To;{8iM>liLShqDJn zC-VOAh$r6U_A-|*vAS1Kw_849Vw2&E@Lv`$uT~CBe|Y%f)TuNHi7LHsUv3#ru622+ zpSrhjy}7*6MhPF=TyN`;cNPwN#}`E6P4?Kl*5xi^vTaXP+okjA_gaO3H|=ymrd#6IW}GmQqqn*CX-np+ z^DBQCKFgFky<7dy?e~tU*_rI`*bdLK`iA&?*-#;rn)Tjo{;_brLWrQVU~2uKu}$-y zFQmkWmw%&rJ)50m&j&H}e^XK$205RM$}%64Xx?^8>X#X7qQmS_v&+j3ucfLM_ zQBBBS=WxXGJx31MYn-~V+~b@#V@6d0firxk{qTy4WRRd;iz zeg3%}#g4oWFKfkbZ`{2~c$?B5iF-HZtS67{lyN(f_wa$*w$Z!wY(4K}i``%HUN5>i z|1{~|+0utRpV!K@`7xjGv(fgxsVCaBem}#3wF4?ifq=GUf-QwCKc_dlW3pfirg#rm(GOl27OQN z&i%n;QH5}Br>@a*7fxY#Shw`nimY+z$>>W7=MLrECB2ErO-XUev+};%8`E?+XRQ9h zL9GR?*jE3Z%d;CEb^J-Q9!lKLN`5}2#da_Jd#Y0UnsnK^heIK;Vvp-*T=X2yKir_y z^<5-suTAXigPy%Eu?qp6L%LFRCVFz?ye?Abnq?bqedd39JbHYc;@xF_Y<(PV2f2R} z8TQ|Lv6gkKyIuW_OO}??M;s44C3dVz*~IQKZWhF(&9&{SNm^A?V`krghr3440GYHZ z<>SFX&6Ewjzn^Z8udwF|KFlO>)->!A0mZMrtf%l?P zUCizozXyNWT+WWQnM#NZRtR5Z{$wyLO-Yesll8y6E;0 z-i3`D>aQ|nZu+=KZt8nm)Wn9aLugQOuD%UeQw@C;P`qMST5NzhCjM zPb&p5hQyYpjL>#G@Cz4fh% z1~qcpBfT_(gXcR#R~t^ZzqU@6ur2i_oiF6RgdLAoyT<%a!M6gg!HMJIny-Fx_m!yfjl zVd{r&>dYB^FqFCZ$NcAE(!jj4_(VjfNZ%p7m?UyrY_0SAiTzIw9m_n$y`?gaWS?LV zOn9l9r=TTS@L1rIDzf}WziOZ6$-Uc45`yxl8ALrpuU+_fnEZv=zG?V^Q;4a!lIfby zx4ykB)7Bh$WpnIBU)4$Ce8I$4#)ZG<4v$^ed%W%jN*l>c9)4HQu~Fq<+C%x^W=Ul> zHAMz>6*lrSL*|`w6-I=x+Jao3=hdg@hNdOeqtum8_$x;JHMKt$%6rV&{;m>BukLwD5I`od^RsTvmwKFg@>%?YPw%>Y;8J8_847lwM9<^u8 zs7Z3D@OE-tE~t_<5;DQb$W~NxFU}afjc_rOO~@y=bn)jpZM&5_mzirdUl;56$oka- z&P@}#^;-QN z501M`yyjjy?MM zr9u%x)du9N^EbqNND4+gD-?vU&w98wt8+f%pWQYEO<$-^+NT;S z{_SQ`M|iQ0r=>;uDNo*~(Tv2%(2sqm)bDR1kcn>fk!F)7iqF0Hrf+fn@wP7*X)W&- zWJKbmd7t@GhI|>tZYKYNL(ap;Jsm64ERKp7H@UW`J7_7s)sDPYDIeru)?dE*!jr~5 z4>lj{{jt@4nn5R;zGKe6XO<~-PmX|~x3}-=gd0({O^2JV+&W;j{x{7ND%kTV4>A)y z;^Fek7Ia9I&XT-M@b4y_f;bLVUzS~}+L2nmTd&+?W%NL9fLZ$u5;`Q0qWl?@TUU&m!AY`>~=A<%ql#o9_0&%J^^%?i#(eD9^k zzA4=*LMlCEd&f81#$Z??I!3=rL-wnOP975ExF<6z5naRW_<+^ZYP87rjY86Fz`Bfw zg5wsSE?bT7t3Ov_rQ0BS`{Vt6mff0#`%%-ezJ$$dO1xHFeK_V_n?sh%7W937;!46b za}NF*hnnmtE?c?K_JWR*8AZmY+u|>X?x=e8WlP1b^j(Qws`<)xAK2Ep!wm)cz8$YV zo^khqC7+jo`q2Iy0pEQb2bvT<4`rWhC>T2IS>)*2GWfDIN%Jf5XlmO?p;ceHhpE80 zv*LHZ_qDEZp=VE@*xI;#B{?D4px0A?GweCR?FMPkll`LFX-!^pv)@lZ!T8xSsH* zt7axZ_OP7eb9Kf@-+IOh$E=|sOK0mATW?wQBUhDgMsID2_1*^$^Qo0Dyx>Z=8k6nO zxV-$cX~O8rE8QyAToZ0xb#KGYm+pSWn0r`Schov*%*y@x{+7Yn%K4Tzg+0X8WPXCObJHecK^Xzis!=$qMS(OR;R*S+O8DZ?S*;@*sEd%@tBU!=^pMAujJ-wL7k&lM4FmX`Lf|MGa9+`b-OOlZ{FH2-`0bV4 z>eqG$68o6PHHY|0U3jaaH(EY~v!E5Z&F-&%%cPQHQ#|J;oSL8Rn4RW*cGg(p?T?I& zJYV9%;|tA7Gc@}?#EgeDzla!#_O)#mnX5h7r#l?;u`lF>sQi-z*Vw&0QH5^pRW566 zo>d;wJ<4l!m`?S=^r8K()g&$-_44QEjvKJ6EwA3u!+7h$_L1hd!fl88>?2Mc7A4#; zXp2%S+|5s}ET-$;vn>2|&2y8|)u$BG?OYS*b+h%9EMC2jt{53V5dAFn+XnSLRm&^e zJ~5s`tveofG;iiB(qX!nxI1sGcYBB4Ndv<)vpWNlt=7V;9k%Uaw(S0$_j-`tGb`d^ z)8vD1zD?#SJCAQ`eK{Tcg;2Ee_nw@d`|rlyB)n0n%F}&Fwmm2}|3hQicPjhI_-Xz9 z``+;trQ~<2+zC2TOKLsq{pm;Uv=&FerKigT533B&d#Wcqe`;c6m-tu9=wto!^$Z^@ zFZQ|dyH+xDC%BZ6$Jj+K>iVu(;Ct0DSgNUB`TRI{TB2ESQqRYL$7#;xM?7=7-F@Xh z{tR>+3(Vx;TP8A1-g-vLVy0XX^{TKDg#|Im&&&*ebTfd$WT5kQxt$HgGJg^Ji zWNFk}{`trb1JUhk)W*&*ZJlbc;~%`2wSW8x|EImCE8qX<+t6E1erj{^m+te7(fMW1 z^UsD1+ovC8@cQGJF`^zc6U;x89lFu0cHQjYnilQ4U&-VZLmPC;*Oy#Lv<=(DRZ@OL zd)ZjPj@3E^I&QI#xEHkVbZdAWmp}K-@=L~0^X79Oh<*Km+Q-_Mj;-gM|Gj^u;bC*m zcRTZsF$imjNH|qa{@g$c(B74iU8KpWNSf6udSASLB+J0_2T%Fe7i)j~&$L|?f813U z-q)lnvbZIsiV8-FoaCF^S&s>L3jVd_@(9*sjgQwVRJeJAXI)c(HLDrRhKnSYrZcV9 zpZ96L;dt|IN3e%p?j!G~K6ke(OBF^5-PcZve_(B`y65Tr5B70K3%#Gld9N9>&zovm zU3S^mgKQb!uRis3D!l&}8UDLE_iPB>?botwyPPH6ovN^fV*aVG%pvaGS|$9s)*i`VWIQ8lZ`6dd6SJ^w%6_J6<*6Z^+;&L zLNTKx_j?heiuMIM!{fG08t0hlwSFne)rG#}N#u{<_$ZycX_e(yjjDD;zkZaz zQcwNkSmX1G!K*gUWItLG`;#?feXD=Xo;y{0WCf8myU}Qkms7>FeY*R-ynRR8Ym`q| zUau=Sv1j+er%hL0tnxNp?&MH;aYm)4^8J}%#~bg2>PvgIt~vF#hCP<$;~=lfcOBcv z7%V@Vd0bjCcW#`+Ps3r2z3QNfTvgPa-4A!~Ft@3ky>r6wq2rq7{hJ?_Cf`t-4qvz; zG5YwezHFmvL04(9ReDhkzv6}OikiV=TZ^A3-j(ST46u#+luT+OF`lw7d$mDFa8JWV z`zi~+S0DLqaE4k1af_d_JEfw!Tb&#b=la$4%*~RKiIpuajrVL%GwXjS(Jbf|y0W*- zp~Iny{_wF0gDzKZ4foNuUFWt4oH4$!;X`hcl{cTxa7(_#ROx|TrBg!M*$28F6}&1u z)8YO|qWi8kU(}fJVQYmQ{0lsjaH&!R9vMm^T=+dVjdLlK0)!dsb@qS??BQRh1y6og94gt(e@32-el80Q?|@AXL}`` zNmd`$`;Xg&a?W*c*wWFtzwL@;QfjGTv0QG@VH+{uKbK$5bIFE0CT&a*jS-kO^|nrX zn*Ozh@v=ei=_Ikhhu(aj9-Pnk@WONLNY2%(4s8la*Hy$^jZI<}7@TXp)u*eJt#35` zQ6pEqIS{%qXg?p8w47gIcBeFRrTxZ@`en@P%$10*bVgG(qY~X>#Bxq_?>ZYjrL@2H zD5GeBeZ}1LrRXW;c{(Qn-#uT}%iXn!sJ;V?O{lmw4629htgLC)d)KL-Yx3#7qfM<_ z=;P;>DIR6SEgyO1Z3Taeo73$L;uhUpA-QH$E2c7#aXi(-F+|NLIP_0%ik#N{pdC-T z{@R+vlV?txAivKzcKor@ym0@U!1>3g%n~;`Gpc_uX4_dw7G!-by?f@yuh>&R`po22 z^zAe*X(zO5%zQCbPdMZsEY0W;{vWlU&haF<|a9IkA283EP(CSBA8D zN3UPHHu{rE|Bd7oNd;`@7phMv&wx~(p+MNhsha&42j^JIFP6>GQ79+%u(@x$9hOB3oZ5q}P_d)<8iPj#3sQ5W{)O}cX!F~hN-|N{n zh3A~_H#v*<4NvEZZ@Sw(+!=D9Z{VQ!Rh_BBAuk48x%!8v{mzp8gXbS{k{A90KNc{k@Sxa7M9y8oMsk7UXJlv z-(<3Hu5`6X@^WPLGADI$#$6jO-CV2?^OnDeIbXJvfvxSdLWP;adeyX7dm1Yp8mj_S zD%tK-TIoO9B0%OhJ46<&+)kgQA~2wQ)PnwESl}U*!n)bj59$S+@4s?a7~;^L)jM;y z@XClcY12AlZ6k-8T>a{3YYQb}W7d{dlbO%UTzfc5AMkcw5%ZQgTl&&u3&X3%w(WEu zGRHVuyJFuf=%q&3rk0CjFf{9Yc$cnwR9eiI>?aj*UA}pft=P@u#$=@#3ER}jb-L+) zOwY}QeK1{fNQrHpe}%+c^?AX{nb|rSzt9h@A754MFjs5}jJ(aDwdUlG+L!ZDFtbhrKdxd^)ud8g*QAjSb_#5GS$G zFU{5hO+FXy*q##jUSn{#3t6Z7WXX;LX{|f`d`8?KeLY>&_e$-Bx9F)O1Mym>Jpw)V zv>gPO`Q_Z5TK0EtK=$?7H^monE8jWte%~B!Xwfyp({(rO#lngsEZX01o=W5S?f6k8 zH<-`i`>jEmJuq8$#jNLkTN~4t>&0K9ICdTqiXk#|6g%D$DsdzSp7OqL zt-bA5aPt|x1+ zJ+(nlBGXFmobrrRQ1nNEw>+-zHTuq+-M>(^FQImKYGrtcOt8b*(FegFJw(6W3iS8@ zZ>ubqCg#tzb&4L$+aRP!bkVzn%;LzQ9&J|*CzK7xCFcssuwH(BHg)QL^0<%Y_8^{{ z?K}-NM6I-%&k3EpK|jR8t!;VwLWTYAD%*Gm+DkU_g!V*&m`mT`ccyo zSNlw4FRW0%W@vbFP2sSR*!5L|e6eYZINgQyO#=hSmB!z8dEu;AdU#nUC$Fpq0 zM9TG_Cgn>Hf)w?g1Cpr?Kb2<;XkiPD9jwar9hO3t_X-<(K+8#Aon5if&(e!|}yk+qnC zRj93*C`>8mSTk6CydNVI-}`bVx_Pmq-ew}@Q$J{T3kc18DJcqC7TxT{$omHo`jNf`GEhn8pufxE{fYO$yp}gUlI{i(n_R!-3PU_g0ZcE|0L4LxQ$4pIOg02 zlAfUdBn@qgX$CNfL&!gg7A4=%)RUn)P+||JWy^Lh$+zL?KTT28)=rfC?^_s%+(8s1 zgopnpckNirJ+uSzkUmb8Bz7O?MAIFM_3{^!R-gDM6-IR}L_UhwM>|2%eIYR`Rtq(B z67iOsz)0O#AlIXfU5hqcx`6D8!)zoTjOWHGoef$G>!|gZsOb`j6caU4SXBONZTzN# zAFop!9R{TGW<6Da%P56z!rm z+q+xA_II$oZizPUWvcC+-9$l3aTnf#r*&6BupB+=UaW(c-9WOZQb^X!>!PL)-G{_GY8Za6Ekv%Xww@a?(~vx zL@d$XdwWqE`&-vg=4sS2``Ouv2dIgksjupgq?bV;T*wf{`< zB}&!uBU0~TJSp~qo$dAiq`WAkcdBrKB5LX*Qr>xp-u6Ky&HWPyBlZ5pk^R5-6#Z}5j|?oD5oV;kxd^ot zkoYNCFL|vCHEV2;B@O*cgT3WNf}*|T1usjqzkdFw&4lG(8-x;;FJ`giy%tLnIZyse z#DgWGea!{p{X@h(T=JfQCCRmC{v}tXCjbAwcHqCU2Opa#^P<=+8u&?rrc9lR z@SeNmx$q@jH&MtQ+S>B7YV~nECPq#TC#YePLMCU*gu) zKe&+}14Kz_Y>_ZS`|R5iRUtaM#Fdi@@EDvR^68`w_t@l3-$+lFX!2E)5~>t4OP*X> zVur+ksjf7ot->V_G5yzOc%7!`t$J7rgXw)3OqY)7TF8EcxFWIO>vE*mM&h7k?EB}AU~EK&Q$Ls2ur?$}1$Lqy!u|8771U;PsTxIQ{ML=>XfroB;bsk?Q; zbm;yNaT7&t1xrU5R`};o_@zrWc*+5*b+np5Cqy%dUg-8FFXhmu+I)6=+j-L_?lu>KRF7T2B zz6OYAl&Fawj}kQqKTOf+D6FsL%;=Dv7)b_A>(B`xx6ec+`mldg!Dpfkq0bEc`3wn` znInxcq835U9C?fp^$8B<$bOP2f=b7TN`x~MAdA??iOPf*6d;e>#zDfq0aKGl)4zz! zs03rSEHV*wP*cJaz+7KsGQZO?qxR24F(jo;$AHM=L^i_2qKuoFz>FF&?bQ~TMFk`| z30_4~z*a&%<*z(yog}Igcr6j#6w#92#`3?iX`o+XBp!5s3Wk$)R{!yGNMxF*N*LLQ z8I?uvjp(@0(P=23p*@vRKu`D~E&mLWLc$taYs54Wb~EDgS@{$iXUDyvfORZjtyU+h=V>fwBlDV;_gqw9Grz5Grtm7 z5u^kDmu8ybNi-qM-^Df3uhQ|MbXF*<&M$E4L=jFyBnqSWU&Pe}rYb74l^|bD1;Qw{ z5Q-W7o2X4_t6fUVCA|ZKs~5mvY(0(0`Y}Xv>H-vKWh0g5M86k^=7eSKRE8PdeGU;2 z^#>GlUg0#QBYgTpTu%^xO=Sd8868O+S=Q0Wmuzo9B9ASEbT5*>*|c+yK{ z*^_KZ=7gXToWMF%QVnSxL45)zH0Vgygte1YDJL=-rei}3J#_F3i^|uSy$kb86$FqW zfuux`__LH|Lp@`3yhzcV#DTZH{^Sy8>zAQ67Lq&yFBbEmRFVok*pjEGkww#!tO%A2 zGz>B1rs({>sh>7SC`mrCHDcM$&3RI?w;oy^JJX zLIW?AWZzw1y6E0_wF#ef>x#YSRD zW+Q2!M;s(2Y`|l}C}TpjJj!At`4KV|5HCB)op4zN`@0g|W+&+pIJ7XJf_OMch6KOW zI5^5dG9a+(;h<2CAcWMo!9!L~@UToDr$f~Vd}uExc<5?G!*pUyvk8?UA{#EKZ=xBM z;YE+Qz-x00oY|&J5JU>xz}&H-GRyIvSj-I>%50?2$vohbsvWN4g#n(;Sh?j9k3E4A zm8}JLJZGTUXL%q|;}#m3Auq{NlgA51&vc?;tSty^NQ@6$m2#t@8*B)oC=R2W zc2j94^ob7|!+S54;lZ>1?69QOL*1zg(3ANg%e$V4PLL#pb_tM}5SIWHx_m#Cu^^Ot zVL%qOU=kT$47d`64&Y>|6M+j4uIqwO!UYNqn~Z|cNj?3Mi7-@!gAjO{O93lUz7R>7 zFuw>mg~8*E2QjtXY?%iM%l7&oQ1|mf5uz||)C-fi2sH=M8)1?@Vdfy_wFuhvmWu^x zi-1AZLuj`M3>5B^zeKcFotp){6d@@RvKAR0Pi{^mN(9}HhbXC&MMN3VJ|d`y2H@tV z2|P^bE~c_&k&%)XWb0mF;!IUIZng5LdSCv+(*Nl3jl7N?I(g1bz~ILJ6j;6QznP!MzlXEe?Mqag*% zqjW06gpNr;HUigi=59Q6gC0!hST@FpBaur4UR0(Fd6|J9gmB!N`&TOoH>vU4om|>r+|*jkff2}3K%qASK-ntE1-lM z>u@k$2&#WqKw|3#oUxXHnjdS&fFt2TH};o=W@I4ug&rK3%aZizB2c6pY*VMgZ-UPV zE&#xWxVm6Tr#k`VAoVWkWw$4BElWAbU*{VRT0TIj@5({`h4VOLD-T`nha8x_{+r4e z5g3*sx|Psao8(E%C|@2-lriGW=C5Ev@i9zSYn31>y1y^U)q@q&BB8%Pqv&jKi|yAE zh0C0{!aW7ZvXd7FQc74!6k$q95~5*z6`^jT#Az5+c6tGHH3ZClR)kg~uAs_{2<>uI zz=h5!LF+$NqB3k~mk2!v8eauTe9`({g%2T)RXWv|k(2$ikH9 z`4NW-RAS^>8rnq#yfrn$nJEK$CiFlB>a88t(O8X87`U|2i@!y=XqFg&R5_P^#)Q3uO; zhp94Fv~dqTGs;;3x!&}mr=5(oj^SEOUQkgG;5?|*XNiJk1g^lQ0gIu?6Bv+0k_REb z@&lk9qXAhNp227-)Ds9sekTDvgwZll7`=mVBNk5;wvwbx7`TW7@^R3mbo&V?0pV{l zn$aeSp)058`Ov$SV502Y5;coqdp#17Fv^3Ag!Ca~^969=tq+5j7CLAM4cg4aAc``J!PK}um}(Zs zRra$p2%xw2KyNSr+Ep5-BMczQ8f7pbj`|HqMucny3`ikkL#Syp6%1@4yjRCHj)}ty zEfxm<#XZv+Fm*r^ml>}CQ;hnEZXI}$DGy#~tOUj5dN6*y#1x~As4`}xrh-}8^v{x# z5h(ORM_)|Lj3U(FJt>mY;BYi1+iXfBYcPV4@PZCb)n+#YbN_WnYhy^_2)!Fqm|D*u zjIJ0%Q{Ho;GQ7yif&oq^Fgjx=m1ac7Hb7Gl57;q)jM`C|hARm7QAv_RnuLE89HVlRSv<@aU zBJ^J@q4|0k>w+)gAay--<_D=b__`h{;Qmb<*d;OuqN|!vl?P3s%k40SrhLB+0;a$e zlGxtEwI;7Jh~pKmVMdZ5{4BufgJzJ2<|7PIEdWx2P21uy1j6n?RTZ@yM zXvLCx&h5apHdv6fAgE_7Aw^>y10UwWVhXFKB`MzY<0&RBpk)+>khC>a@XK~c;?nUi zNg$XZw12{7hhITwNXvwBzQSnx37i(Rg7k?qI0&(VmQDJGgLhUC+uwd+U@L*R3=M3B zS-ZR)A|=%t3YJ2TGa54tB*b9@6=lv$qvLD?ef1>=4deS0Dw+~xT{hsrNvLqDMS+b_ zt$Rdi82^nB6vmP?OzTF{8bZ7*4YO(!_z|o~!w`iTIZ?(Ya7ICOktQ(`k!?K`o6{C@ zeWyXCnNXMnqW~`R#bhyBG&1GojDm>E1getKnHw<$FI^f1W;>`jPD7m8Wd{>Rp)rlP z(hjQ9YdsCayb^rVum|57%yBx%9{k^Ig@XorSeYH%gab(jsCzaCDu4@Z#*ADj-T_hv zZN+I$Q}BKiWAdGFMr|{kd~V)J1>ESTH6sUhjgANHvty*~*kAYHS{LjX`O&YMzBu6{z{--+aON9 zT*B2e&N4EgvTdM7e}&3$Vk06ClHU%_)n?-KuI*3&_UjlRp=XyM)zj@TmdNH%8Gd|4 zF_yB#ucLWX1tvti%*c+ycR)?e=i_wM4w41obs-MqouH)Oi*XQ_%_xSA(Y!Ky>bqtI-!maonxCxg~CG zWy2Mw=AiRQ?E=Hb{8WZHsh??aHFtg&RA{9LE_%KT>foCg4y1NNxAT^w0uIE@#q{5# z%ZPG!!-9ejR`-}Apv{5CcEdDDH@!&LD` zkx2+EG%Qs2f?o+RqhrRE)R_2b#&6M8Otc*^7v^?MOKcxRqJRYs?rJk}BJw^c_d9Eh z5k2> zVUrisg55=&86z{v;{&ygHz74V>6qNI! z`U^{1VS75RaL0#aN0`c_0wU7%h5mT#I?kN+C2b&(vTti015rM0@`pYqeOUrA7?@{pqXH6mIo>LfukO<7;%T`_0KgXF8t&+45QsjaJs+` zBG2zB4w&+A9oU*U0)1?`KLm7S1ui4zL;2x!VsX|A^9LiJ>K2Xo!#1u!GY*bFg19Ox zV`4*U2f;0mb{d+qoQVge{s!N!9fb4-uc$I6_K0L(EiQ~xO^zk^N=Ck=2dArR~Y%+ut-GYoZN9P_VEZjUZ$FWuj`YU?Nj zU4I}rSWJf!BA_korkJF#1rrCdI}F)vXT<60FH90>{v~Af_%LL}$cocYp-kxdcQ8UZ zr4b4OSt19G%svPv=SMs=%;rB36%_4GOxsU@M#g;vwADpu82=*>18+oWm={N2(Ges` z!zcyAvcY);4HFX#lSqO*&b$wScu^B%Ww2DwqpVk5&Oc0qg`u zf_cLmIDI=3YV%hP4lX4@)57f$i>B`!YS#;;l{^m# zn_U3 z;DH9tSWB=hF3*Re!G)b#7`>msql^7jM8&c!94Ipe64V)Bj1(G=fmS>YJBb*OT+PCb zO+Sm%hkGoTklKtQV@dV|@g3M-Y4p^bg$@0U1rujnuv8?J8AoD8o8n-;G~7*PHWJEV zClM2~#=|gW0aslx;1LfqX}C8AU<>#ni5qptLxG$Q(J+PyV2Uq@hDpVkf)E`-9ol%iPp@s2Wk32cXF z;O#X>?E8z7Q?++?90 z9?lhG$`a^LGBn%UCpZYsg=V`W3)*w{mS~@;z!dxm6g1UWJTHr)Zegt5BN0uQ(GizycdG*uJ1;D!5`ahtqw75W1AT z-1@O4h1~uJSLja#XDaE?Ko&HGS{h6XlT0``GYfuDws>;Wz@h^iPWPvQA5)w-SeXv{ zMsd72kpBx!dm#^8xRwqH)(YbEYXW>&XFMIs^GjqgRR)AjmKYB7*jVBEMb*DqFDC<% z%1Pm}XPm5jsHO6s><=c3U4hHwcv-ozb8sHykVzuJ4IuBcAOxZ^p`v487b6SS(h8!i z{PWI<4JUWZdCUD#y6fcJGMAdedka%~_L<=mpgmX!y-z4!0F2Mcun zCMb*CfUf-69albh1ANQy!hzm4RvvsG;)Lj;^R3W=8VUg+8pqEFN_4Y;Ii4ZWbCgvGCBoKMA?{4gj58(D>&VF z3nFMk1`a+(L+!v?mKS-)v(gS2^U(D%BgbyTDE9ge4%%)*(vm_9h$7isxJtCM7zgt= zAumesUCM>L_@ChP-P^2O=;;ZFl2MFqd5+UkdC+xAt8fsM2Tix~1r8b>v9hCgc~G>m z28@Ao&8OgD{|orF=?<7U*+Qkok$M3*{@@OrOQ^!R0H!^12X-{#J8_^`$qMJV1(175 z^^!`r=*AV&?!t!e*S9$MdlzCYpbrP^jgaeqC!C@8AnR9f5`g8Ae-HBD7{h^o3oA3? z$%jh%_GKvp=NA(%8G-k0+?@Y zp}S+c;`d<1%3hb!^5kS(DQdU_!QtI%3BgXt8gLe7*+nVu_`82r8- zSBPK9M!C$exFBqL1g;frz-4yYkO3vJu-=ly+19wiT0KyJ=2RkVx5XGKR8|DFtmlY< zJ%s9QxZ1(TFzIe^!9m+&=u`D>IFK)fDhu0(m+ee3sC|arMy#O2#SqKpemLlNX5+!e z`^B}0QwcaZ6@bg)OQ4b4f~kNNeJg>mi44OTk{25%N)3i!-B${!+9Pn<#}|qXD}zOg zPchlH6S!>JAL@*9X@;i^PWF;dQE3LWsSLdTdzOYt4T20PJ3iHAU_>GYm)SjmYjX2D zVS|(O1ZXitr40zP>4@$bNi6v(td%~(M=tR*qZgQ7aP~jZS^^n{hkt6GPhp7I@$f%l zArq=((~5ru7+h$XrD96~&|5eL@g;PUV1(8dF;RK}Q4+DQd$D8C#AFz?qmvrrDY z0q<~NQvs_#-H$kEZDkWdB8c>5-C#;p=&?y4CaIQN6^Fl{Ok;=bXG z{6}ybCRw^$gbEs2ewFOBG4!1Vf>i=Bv`)q=fQ8JuCQ1HVLI4UdWa>L8$8RB`Z=#LkI3 zc|n4mw)?{!G@!kiFsp?t2EBlaIi!o_PC`vDV7UEafB{(S)WaP~BE}dHLHR1|Oz1Oq z!Q*y4iA2vL%z@4^aLAxtlR*6hiZCJq&!IuG%tqLc*Lev;n~Nw76Y~;^UL!`se0~Z2 z@}&d~W7+`iy-l9Vz%`);m{l7UX&66Y4lb0AZIon-aL^V^TbV}7t`YJ#P^B{Z1e4V` zcq7BHcoTzY6L=j4ONAC#`HIMK@S|QSxRZ%8u3lAMVq3`w*Lu(dX3yE+fVmmsD|a&v zT$>@btF~i67I~U;h~qUg*$jCEIpMT=3k1i=ZVZGF?(W6@>Y>X#q9ml&3TmRB7^94W zT0!l(4+ccg^HyjP13w%{wn20E2BNG^2*cxTP<|%<}*|oOt+m-GPx3raUeV?!~RMmm)rk*T-^l;E8;71>*3LI$Y6;#yaK^kUFH&j9N zFqL6P>YW@+aM$l*JjjkLu~zs4*R&bo;Kpx--PI4*=9ynZ0V0+m=|O0@_mdoKaQ7y7 z=ra1xj5DSH_ox3;fCmHGz*pkeCDv~-;tIxJIp8KR?39J=4W!Fqq0-FA>_<(Fs$}OdLY9A zbt(<_;)!!|Ah#Y!FQ$#tI{3sk^^V#By$i+KQyM#bWE!2tAIxbjGe0m26u@wQ*a!SRnU zCH_6j33nuafB<#7vXquU$Bdw9K7W7$^rbG9aU&NYQ6XgW5oCNBRM`eX>TMioB2MT| zry)J#Am~&VVDu(}&?9tc5bkq|e2o2-MiYb353ZEpz-kCUVi^Xc&~5k(I-*4RlOZsm zS%cf19)fYOBfDW}|3eKplQ|5-qJ1OE8X?Ic#t|r$c`FWfj=&6lp&bKz3F)0U zsqzV?#K~7UxbO*9bO+zy;QJ@2=7Vq1%27D^WE{gtQIzo-VlsaeDz{+_nS2KSe~&_% zu?Y;=6M80*$rz~Re}-t2o54YOAEz+h>tx{;RD$MLjJ77cScbBupx3%ha>6yH$52m6 zvz)ZkiwrZapfL%N1ounBl^0%EDl3h{Qn{6dM&>mRyCGyY8m4m`O6AK*!*KtC9@)eB zFD5M}z!O<+8ijKcP*oNDG)(^l7-15oGEM|{5*2VFRu(R}j*U&m{geN%t1AzxstV)1 zbA3D?;Jp{{vAhG12L=Le;3&!>id*Fp* zkr1#UxQ(GaFvj`Y45+N>9^$)s7;vC zrz-^DQ*kriyFewIO|7z|U1`ZJSSWqlhpD@T_2=sw zEXF}Yo6*wSw+beY-PkUE5ojjJ4|Y*V3m&PByTz}UX4YY|u(1X1hJGoTQ!Th}^+w2% zXobX9Y>)fy6D=7@i(Ao|Qx8gTq!n&dd?!KdZFo?FN3Bo;2%yD+X**;wcB;FL%Wpa? zndq<7Aj;XJI;i#+wCaOxa9{=Iz9?VThIf+H$1Fu`68EW2c}H@zLvig1OBP6}2h;!> z+m2DQ<(#C~wqy9O!&6=uyV#D#-;d|F0I7H2^VPrT(p}WN{0=0)UzK3_X|+4OQ+u!f zGSB$+a_u##_52w>t-`x-rW(5jVJ^E)4fC<^oseCx7qWcz%uVr|MAJLmX}0T>#&}fa z*9cNP0L%(n3}L04r?HSW`S(2hy&6fYC{%fz4`u5+D8$B}VA~WrsPI@?W#hw`%OSy4 z8y{_ZioRC3m)e@pQcp6T!p69y^e?7G%PD$-apZDDN;+8KV_1UQ0+@LYt-Dm*sz9-r z3t1uC6HPWJEO&I_4tk^u@6XC{Vqh_;!AK04>_BC{>4H*s5%^%r2C)SQV6YSm>^zIj z#E!yZv{)^Oj@set92^A*T20pCg$w2^8W#YI9obU0IYo=0cLR8e?Rb@w$5U}14f|za zwj)<)#0e&l9&@1S=8mu!Ck5E?v^(U0sVW3H2*oQIxUkk0RVf|g!^{!PL*pzagf<1D zUMGiYzIV16j|zn;?5D@Xua}lMc?PSWCc)Y~&FOO+NP5(-=$AN;5Jmb0@@%n$H^7=e zl&?c(hmb6qj7kODaaCs!93EaQ=}|!#1C!=T&|IK})7~Id{6dLfqN$=A??wHBVW+v& zhuJqn!;bqhPTh=s%9TPtXXY>PQO$Wy3ze!k*tXLX-FOtM#@U8xy^u}8n@tlWlXo^2 zDoG8Pw-Z!&xelisrYw*KmS}F;rNX;Xyx_Fx4wdJy7My@sO!Wd()i}j|O@ooMYou(y z#*vn@jvB&Hv8}J5s+l^B&08-SeTf!F9V z(7k;cek6y%C|+9_IzN1&1=H*>m~b4H%;#Y|ll}rz^O&HgvpR%chw(%j;zCujPYMuA6)rx2?L*|0Q7;!yXQS&R_$VCP(P80y z9Gi8{VzSw%7bF;e1Vh2tKinUIi(Eqpw=gj!0w$^ucV*O1fTBMoaQ>>PveDurQJ^ov zv4qZ(k!Y`tS7{mNF;o-D2ePtj0w8-W3X;c>mmxrL6eNA>CBWBc(wV(cf z=_Sk-gb3q6(9Jz;ClWbCX)MwInQVF?+6@2 z`O)Z{NqFm`@JKT9j`SF`$bo2{rUWBhV_FQFn#b@F%Hb{snxu@z;yKN($Ix#vJX6Vc znFz@ps)$Z7XUzl;cPlj!hOjqn@bDC6IEIo@@IqHz6RJoA2-0We13GymQtjK#vK$$o_kiwrgF=e<0Fio85s>HktE^?>r!+)jjp&;mV- zijTsHhvVSt=$B35`KfxM*iGPlx!^yZXY&8V@jRvPf==Y3+3`G8$t^=Z;!M3iHJ?J6 z%ke0)e}zHyrd~aGhI0IM6P3+_`}i=5d6%x~0oC&>b+V-+WfuusIyLp+Im)7nPHMc8 zQfVS1e{0YE=!wNuz7$X36O@j(eW}$6JXfjO=u7>bz{e*X*Q142 qin6WNqz0#;xwoH1v_q}#34dg)9iL~x$9|NbmAqND`x1YR0{RcThGY`} diff --git a/src/org/usfirst/frc/team3316/robot/Robot.java b/src/org/usfirst/frc/team3316/robot/Robot.java index bdf0543..3efd5d8 100644 --- a/src/org/usfirst/frc/team3316/robot/Robot.java +++ b/src/org/usfirst/frc/team3316/robot/Robot.java @@ -117,8 +117,9 @@ public void teleopInit() {} * This function is called when the disabled button is hit. * You can use it to reset subsystems before shutting down. */ - public void disabledInit(){ - + public void disabledInit() + { + Robot.stacker.setSetpointState(null); } /** diff --git a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java index 14e855e..51b8f03 100644 --- a/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java +++ b/src/org/usfirst/frc/team3316/robot/humanIO/SDB.java @@ -202,6 +202,8 @@ private void initSDB () /* * Stacker */ + SmartDashboard.putData(Robot.stacker); + putConfigVariableInSDB("stacker_HeightFloorMinimum"); putConfigVariableInSDB("stacker_HeightFloorMaximum"); diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java index b9237e6..ef46e45 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java @@ -34,9 +34,9 @@ public StackerManager () public StackerPosition setSetpointState (StackerPosition setpoint) { - if (setpoint == null) { + setpointState = setpoint; return null; } @@ -46,6 +46,8 @@ public StackerPosition setSetpointState (StackerPosition setpoint) } GamePieceCollected gp = Robot.rollerGripper.getGamePieceCollected(); + + setpointState = setpoint; if (setpoint == StackerPosition.Tote) { @@ -77,7 +79,8 @@ else if (setpoint == StackerPosition.Step) { if (currentState == StackerPosition.Tote) { - if (gp == GamePieceCollected.None) //TODO: check if needs to open for container too + //TODO: check if needs to open for container too + if (gp == GamePieceCollected.None || gp == GamePieceCollected.Unsure) { openSolenoidGripper(); closeSolenoidContainer(); @@ -111,7 +114,6 @@ else if (setpoint == StackerPosition.Floor) if (gp == GamePieceCollected.None || gp == GamePieceCollected.Unsure) { - closeSolenoidContainer(); openSolenoidGripper(); setpointState = StackerPosition.Step; moveToStep(); @@ -119,6 +121,8 @@ else if (setpoint == StackerPosition.Floor) else { + closeSolenoidContainer(); + moveToFloor(); } } @@ -133,7 +137,6 @@ else if (currentState == StackerPosition.Step) moveToFloor(); } } - setpointState = setpoint; return setpointState; } @@ -149,8 +152,23 @@ public void run () } //FOR TESTING. NEEDS TO BE REMOVED. - SmartDashboard.putString("Current State", currentState.toString()); - SmartDashboard.putString("Setpoint State", setpointState.toString()); + if (currentState == null) + { + SmartDashboard.putString("Current State", "null"); + } + else + { + SmartDashboard.putString("Current State", currentState.toString()); + } + + if (setpointState == null) + { + SmartDashboard.putString("Setpoint State", "null"); + } + else + { + SmartDashboard.putString("Setpoint State", setpointState.toString()); + } } }//end of class @@ -323,8 +341,8 @@ private void moveToFloor () private void moveToStep () { - Robot.stacker.openSolenoidBottom(); - Robot.stacker.closeSolenoidUpper(); + Robot.stacker.closeSolenoidBottom(); + Robot.stacker.openSolenoidUpper(); } private void moveToTote () diff --git a/sysProps.xml b/sysProps.xml index b3bc9559a0a88a9389d09c60efd53cc47e1c3d18..c7a1001bf144a1500159fd22f1f6c3a9acbcf48e 100644 GIT binary patch delta 36 pcmdm|w@+`wK0$sX21^E01~Udd1_KbB?9X96IYF3ZGmnrFD*&xv2r>Ww delta 36 pcmdm|w@+`wK0$tC215oT1`7r~1_KbB?9X96IYF3ZGmnrFD*&vJ2r2*o From 09d3690fa66a52c65ba070dff60679a8b6a90f8e Mon Sep 17 00:00:00 2001 From: frc3316 Date: Tue, 17 Feb 2015 08:46:36 +0200 Subject: [PATCH 28/29] Tried unsuccessfully fixing bugs 1) Can't start drive commands in SmartDashboard, and after a few seconds code crashes 2) Moving stacker to floor takes extra time, need to figure out why --- dist/FRCUserProgram.jar | Bin 1780392 -> 1780426 bytes .../frc/team3316/robot/humanIO/SDB.java | 3 --- .../robot/stacker/commands/MoveStacker.java | 10 +++++++- .../team3316/robot/subsystems/Stacker.java | 24 +++++++++++++----- sysProps.xml | Bin 5950 -> 5950 bytes 5 files changed, 26 insertions(+), 11 deletions(-) diff --git a/dist/FRCUserProgram.jar b/dist/FRCUserProgram.jar index a516a349bfde0d2227b16996750fda0459769a6b..6d906ac0b80b97b43c75b2aa7ce3dc61d79ae920 100644 GIT binary patch delta 25482 zcmZTw2|QKZ*LIJ2zGmlMgv^;EiKK)=h9+~NG)U2)h(alaqzt=EAwyIoDpAoOMTU|h zWNH$LCW`7?=N|9v`hV~5ci!!J*4k^Yz4pA%xm{@UuW$1gaI|IT;A3OsVPk7qdP+bY zYhHTF=sEm9QIH~!wJc54p=c1uouUItSsW#mLZoW!7Z~X?4qrxU%vH}wIe9`DX#{Vv z5RqF~dM=^vD}6v1VA&hh7y*I~G?+`kJOfXRNI8sZC`9^j{#!iz=zEa zGg2P&Mn?K_aWErwvY0JSnA_{jaP^F{8iDRPYZA$*vmueFx|j&HEOoMqJZSgmC!%QF4_7~b>k z*hzR$c3_t-1DEVR%+NE~8^lO22Jd5}N}*RUUZM)e#zTH;Cq_nilo=mf#1QR|$Y!Ln zhedb^Q@U~M8TeFu8pEV^!Vg9zRg!H9@$Te94DmSH$q@UUEhliIeEJeXyfOVVgI<$a z&j^J=fdxTtDp<|Pb*r$Fi@?EGYB@y+e|&ydy>#VeW9txSW7ADs?5UU-cpVRSC_byn zeos^btIv^13%nE|pCD}`8s8GdMsIr6zj5Db+4hX(n>VqSZ@E^x@>1LN7yDNadUIZE z$L@)quq<`E+~&7^;eO}+J>%Vee*-q{_P?5tJG$YH(dXYi`@+8-XebLX-NjeqyK*Pn zQ0Wcvmjmp1E~;`bH=J|%lsI;m&E`Qz_<~`y(}FFpon8|ics@>;J1YhSRV=^TND1SZ zl{{9;_OMry^0%UQ*EYSWMZT0U>;`9`$q4n{h(K>*#hi$$o#qbB+|H#a7AzIlBzKnUNai9__On9L{_wfsoDoA@i3={BH6W0k&9FYvcuWl z`IN*BP@YJATgt}I(Z~^avv>DOtIce-qgSY3jvdnWu0PLrC$~50P@TAGac}t{Rq-&_ zyNP_6D@P?b9r(*KokrJiHfv0z9(pfsTGBhDzb;`cC+Zaa)j;Y+>mk2X!_Cng*IpY0 zRn03jjvra3w%l#|_DU`9b%%X#SU$7A=pAmdBeyNy(!QEmE>^J{>8{$7Y_Y9eQWO9YA$=#o?k_ueA{p)Fyx&7 zv5!0Q;sT!fHmrD=@3w7nmh<>)uLS*yQ>{w4e~RurhkHfACdIjbqt93$eEUtW=VVlz^XgkMFO^mcO4e~S>ZUJS z^0NP^?&^KcKW+Vr`xkiBsugGLv|n;E`l{8@2H!CE+I^#*ys>|J7D&nc%#6`$FY2G1 zh>V+6G$FDM?X;>rIVL8tsJ2;pgT$gbosCl~YfDDA@tzNz?YKEFd|~u&uIe>oCR3T- zpBG*-^33QlkO;4twOhzfb57y5{Fp_3%^H6WRToXr|7iD3{kdDboc_3C;&i-++G=D`%pT)7Rn;MR_;bTW*jCNj&sPpnzz0DM)=T=>)*rN zw}0B}G5h)k_w7qIblUHb6ZMOYifxW8GBVlI*=;J`BA-sXl(B7Ve3bgltW6DVLjq3? zeD=?-rWEe^*d@IkojjWv>wUVCHd(kZq9dzjM|_`$*K?ae|J$3~jjkBql~%sA(c@mZ z#|N&~zI0u-0vpbi*-^alTlAwYKMOx`J*rA^tLxsAdqae)3@hcw9VfEi``jrj>x!-1 zKiM%7vblR)guG{jQwsoQH6(>jcd5v3tN~OKkRR$ zXqIp>_vzJz{kblwJAYJ4+LjHRx)6MM=%BCITY=RDH);1}c06kKK9TZlz^OYfR4gl8 z`nk63NP5HIBVG5)Wp-=dNb?GBjuSJAxxKh}^Xo6^FEp=fRQ>L*s?DxBUV1jaHcVHc z>+ew`tYn>5MH9`QyZ2G;;$z84%@@LE=PU`HM|pU(;j2K*Y@hUqmu^P~wP*L_1Re-E zuy5@|MbxHkdd@Be_X6h~Q@q$F(;dC*s*K2ZIPIHNxZT^;o^{tB^GvoHyst4$eZgBL z5i@+-GTSe9^1r;zyAENidN)+PmBX8aEXJ~+kSNf;Fh z_-!w~yD|H$!wHi~r$-W3%KMdaV>YPGk6dy(M@+5w!;;4-i3twogGZ;!{O4Mo>fa}?zJSlZurlG0PIzt&E^dsDaURR2?KHc)uG!SoXdFGJhze04te z=8e?+D}h(ig)`T3)VgyeE&N5@lu2Ju#qGAI!pZz*oVeT%JJU#kcP*XwMCRxoZ8n(Q zvbbRQUhpltl(+DvKH8J}*IbT{dn^CY_x_=`{70*-QLj~3+(3B65sw|U%e#)&1xCNG z@w3Vj7k-x4Irz@0Lf9lBcj(~&+e%&aF(q-AU@3>eCzsCG)*rQK?DD5hrEPsZ+-uLH z9N?7_m!ZFRx$k+Y=HSEx46pJn(s&#!ynejb?~Ayr?#Y0AR+bY6hiy-Oi|T5QXFssy z@)n_~@wC>6z$Brz6~F=2(YQYxRB&DeNy! z)Z2gN)X=>hrZ%55e2%6+ToHW8bxdjG-l{j>3gJ?q=6$1|2v2z}O4|2^x!Jv$HV*`2If z=&@Gnu(RcZt=LkwGU=KS#-2|;T@Rh?#JLk29`F&{wwDh$7`wafT0X`$bnsCTC-B79 z70GwwJc&(B482!PCkei6+w&8|b}#YQtK|f=>}+T36=%I(Nxb)?Y)c~FufY`zGeoK8@9=*+W}+@-@xuuW zALU0v7+cP?(L{#!Q(uO*2y=hU&_4K8nxS>(JDv2!a0@0+gT1;WcjDdgW#MaFSBWjA z{yD0-+(nW{tw2%HSu{S`V#GpdOxZ=!#dP9&hk&>4<9@l|DY4%av#}gym$!#Y*8V)N z8LDD?EYDYb)wS-q3%h$>cDEY-{PFv%6x-b3tl5#JTyYz6C|WDy?kCMr9;yG7YkyH) zJwI=|Rq@E+nc8&muPZelT#>#nY7t)E`{rwx@0t4fJ6;RiV(;63C#3gPe)Hx2Z{OZr z8eHI7XVeh??uAuC^M$;)>lx1?AI-IU9;0oNnr7p)v1{N@>1-Rb`(c+|nr{qmUV7X4 z#YtI*iF@iIHe%VsoYxx{ewJ6$y;6|WdR2`#JXzti-KV)*((L2smTz2od=X!a>xfxt z_*KrU<-RhV8pH0z36m`sen#Kh;PSIG$-ls*+{U=MYo~qinOSf18pNa4P)m5{K3u=c zWOQp=uIb)O0|_gnUe62JA8lIjEN^)Bt))X&eggZtd)u8=S1VgAc|n_ZB2ekIkABei z*Mp(+xx$P4DkJUp;4XKIA`QEY5|-ARn=BBB zTlO-Do&M~qx}~VQfbHL>OOGmK@;{NPyQf*#S|oqfTB^xlxy@XG7hWC7r+3_~V#_S< zD3c$${UvPOwZLrHGQM$}KSJ3!GV!mSHG9JQKee7uKfMXRx!)+H zEv@>?qb=dTzr`zk5PA0Dd||}YQ?GiC0d)-r!XnaT*o@YveC-{BXu*ole z^p*QoMqX{-ZGg7Ti7&XOi#{GKZuws9bbDycm5fE>WfrY((#}sji`o8-n{^f`6Q4Z8 z7QUm5*!pONN;#@Q05Zz$c@w76vkk^A;?ELMa&pC zvZxfslyhSfoubOam?gGhM}7QYmUzmKC>TWro#deKp(}$pH?kPSCBpO8E)Nv<760>R zxk_2Cg$lnnuU`$Dw@Qnvye99EIW?W*(ME5PYXt>!w|*Fu3su0@sR^eXd3!hZ$bQF* zb~X!nPA!emSZFg?`{mu!^HMsmFJ0B_8FJMSxdglU-__%PKTr1jeeq}Pb94`-{Y09G z|GhtInRg?3e(6zb7t8o`c!#T4yX-ZH*|5wiP)7BPz?V~rxAsRm7o16t@3qVgHhi%0 zOvhZiCjHR($2^I9q|bZDS?a|fS5rtA9$3O7Wl^CdUzoXlTYlPJ31_i(bagm=*f_EB zQ^l9u%k{CO3B0yA%&s#Oz;F_IA%$=!;!@oNqii7`ecDH-E~y$fEF_1$zo^ z+h*-^wbL2!*yo}3Imw&1c$2wN(0GFR`Z|qo`{MXlt6tXZa60#F#rF1w%?6>XA4@B3 zwR0`Iwqt`KMd`ceSXuJ|E7_o*!>DS+{nF-Q>z;``tAQZVu+X zUeHpy;d}8(aZs=fG|rs(Jc0%fCU_U^4fz6dycH@r{*6SJ#C)+>FiRI`H!BKzwIcRcVV|c-s$C4#cD6bdDBWQ?|uEi z-*+_%l`2O$E8U985Y4RJE&A$=+M}o}n@5MPs4Bm4nP0oqx+-eUtx7(NC30Mz+IN?p zLT2+v_ zSheR5kM0EP@22l>?OxM6x{7N_)&V?9Bp=IOxtC{8$%GbmZMF2c_|)mr^D@C*OBHF>XLQTc_OqEw4d*JEir0$Z+V zUcGg;^GW$g(W=>eB8@AyCKj)sFBRMDcGWoNef}1s)8%%~*(r}5Zt$g^y)MvL{%u$> zq}3;+)~W4&%Hsp!PxhFmNoo~&8^02J-tcg5S*dS+^x1VG7LG*4vw3G^W@5h)-J2cGTzHo180uck=Fwzp^bkIaNLB zWJdO%E62GE9FMRW3Ak}qY-TH!z9HFvQQ<;$xmdSN7ye4PWuJwqp0LPYuE+_QB1y-E zC%rtLoPU=oTzX>5?7~ClvpHTa%^KnjG+C~6NRe%i{NnYI_Tj^tkqzJ8-u9X@^BY+k z;TP8T!m|Eu%opwT$CKEN2KPuD|Mp<^(gUj=cs~3ow|M71p={2m==Kk(4`dYQN*CPj zmC2cV;e2v%#4FdQu1U-1`o#XdP-&7dRhud-ox5A;``j)41N_HUh*t}W`36m8j*fLH z@^zn*Kk=}cn&+^}vNSt9x7}l} ztEbFY4XfJqZ>G6d*VL34lpj3r`klKme^K9Y4ZB#bR1#g^yYuxpA+AOcVs9ogxm()4 z>G*Z*uWL`sL*7d619_U61z*F{a|dEI1`g^KY^JJ9^76}N7w_~O_{H6>8~f{FkfvLW zmCsM5fa`1Lxx23Jy5&6fOZ&^*QL~&k1=l7Lh9{5R`mHDNsX#m$AD&$;`w-1PQu65B zxMXs3@L=9l5%tjJ(pN58`0bY^6$iwZQ7>dQ1yW6@6Rgue6?Tzwn>}y!!Y%L`DK<7E zl+8`iBIako@H}V!V3{=%e*)w(x*H9ax8`2wJ$Q}UX`t0%pp|Tyr>$!)P`2MW3hU>&E_t;R<{DZ!f+j{F19MSj+uo zX^^b@XW@SK33;hS4_-ufRAyeLxBudCpXEEWp=;uyyjgr&#RTtlv&SzA+J70ipF1_$ zL4DV|+hfA?M)gh6rV_I#o!;2RU5DH)<{#53{r;9J)ECHO9hh`~iZ6D9K;zX%oI7RK z`wnf>+%eGq$^Sq`ZMacIur*tcKp)2)<-SgZJ-sHBFr$dioTIRujA5aD+(I_*)p=kb>-*}@;zwr`alDGzVcSfcW+qOo01 zw0A)9G3zyFw9*KEZT6Net=vvCNONQ86E&fSPjRoHq zC%>D!3zu8SZh?_Z>M8Y)rAnv>@+{8H5oTT4wgNUY1RL{eRSS;|MRXJ z+(I=r?WY`BxOP!~$X(gEi!W5#I;_QYwjbj9vNYpUUV@|6KGY^PnQ>yZx7i+-pK8<>n|t{G`4FEXh=GjRR~lmcj;_kpI6@=wF9rNVHcH48lzr+)c&L&X)0<}T^f@;mhD*>$UAJ{sz;J8bJaB~*<@ zE8dn*$s@k&D~marRw(8TeW_^Myem$5%K72f;KdK=V=B1wz0+fgKKcfkuNA^2 zXKNl^+#I94YMp;1=bxMN-YFdlG!V`%H>HH?*j7d+pGkJo?ABEsb1U^7zdriP^r(Hv z!-Lu)uYdiODxwMd7yaKufE)5+qvPa9HB!;pU*Sos4h&`ohKo; zGAQ3cD9t8ASC$A83G6!$6G6Xf-otGm5G`dg-pX`yO?g?Z#WhkQfdV4FEuUrJ%Z*DY9RXq!`; zuKL3eu{#cf>k4kQmZ)l03UfAPPVBUatTn#!wg3%o!MelN_9>O{sb*_s)>|$q3EQ{u zQ}~dcAMU1MuRfKut+VDBt!#bI;UA_qW9K~`qmM@}7M4xioOq?|wrA%4n9(HL5ih-y zcg`#rJYSshC+YXFu&GUiQp5aD9SizD$~gxF8Ri+guR2{8^t>&}!@v9UN7>>#586yT zZ#T3hH7;vD+G}dJOE`Ila<%;JvhVXX+)n1`$A)js&DF$m57klYbLvaqXy%)&4U#mB zUz1iVaP?!n_a@2j@ofpUnsxhKCCg5>dse4xq!%rFeVmV~yz9dK?)m)VUS=bfCL{N4 zx=w1Fn%_T|aCDR^?x$sP*PBi68Fu(cO{i{T@ixEPvb*R1dZ?Ki-+$@FhAn(A2HqM! zS=bh2SRcOJ%x=%gERmD@FQoB3_lw+r$}|73I#y6pXKLPuHO!a2S(7}nv0i*>o6{}D z=nx5Rei?;lH3PZlMn@lUX7;T#-8?yFy8M^=dbvildH?a?OoiW1?pFY?W zZS7T}BjJ;KHOI=0;Gvsz|dI;tz>_Vu-8{Jzpp z3ynT+-+im^e!p(GNJ{78C)NqSwpksKw=K_FUhY%u5~rLa`2P4_e{tD%MG!Y#y|L;f zePcp#ia_^a?EKyjZ<{yl2(e(l*5N#V++meYoNF>8#evb?HroVCx#rd$ zIivH!=ZH)6u@Cp;O688W$HlcDb9#DW&V!VDE!JBTCdc-t4Mmvnp8v5lDPyVCJvz49 zvSi!7VJT`z*5YnNnpKNC5@mEg#AT4sLtK?0jUM8}OKNoFA-;NANWAn# z@^!cukshkUHxcQ_I(#FMIzGa;5NYKj+>=Q0$G9(%Mm#3<`yWH0fGz6rH4K*-6}VoH z6EEt~lX`qUk#aTQrbN250Vi$+QEUTFyr4$y4ft9j)qR4mA=2n4P!&kuKf!kqse2>7 zlSrEy@l_1#-jWcIMNPOl!A3UWn~C&e6TXK?y_)e5BJFG@u~Q2kO5mmzJcdZ!p5jqN z+B=1HfRh;m0ytf z^b1mt^CiB6;HO?e@K3$O=MmuXG-=#URuifvgRZsXMuc#r9rq_vj}F|2NNYN9KgM0k zzt`?){wuOcW56o*syb1xKpj1Og{u?#L`j(MgTy{x1;#zFkfSXH6K5yB^&oCfkz*&w z3z>3ddEzel`-g4Yi!e5}EnLK1^1uIbBTH)kvm}}*|4MR;;T1-G?`?UDUD?%NvqlGkQ*4xP{r>ok2AJowr?xQT3nb@EVsm}j0A&1wv(*G-B z9#fkrVyt^w8%K?=apLYAb-ac;S-zg;rI1b!F3GU+@0Og6Z5h)FQKn%ZQycEhgq4`9h@nZrPLRZ`g4O5uWj$qcKGgwou^ny;eB_$iI_ z!T;8w`?o;*8faV0(DwUI6sMo~>bn?2onidn%|9F4;u-4EsCNK&WYo(=?ofyU*t`LC zo7o6#lZ4HM=)@ZwC+cFQ zgR?VBulvhzHd&S;!f=)_PI-sRu=i0YiHpDLAtQ_;Dg3X8lA((m!RhQ24hkxzQs$uQ zcVyX(M84(!v1d6b!lRGL#}KYTIf8VCa6`&P0DvH$YA! zxH94&#^+!w7(f-RAI3GXglRB33HQ=B3Fg%_bFhxWkEA|?2Iq z@`e-+6h4geQFf6cVQ!2YH4wVD2tpmr8o_lju6abMYcYF9s)|}ha2-lY%4gh${pq}a z71BkMGBheG{fyJt>x};KDoA=1*TVcwNZ)(SC_-reD82x@YsO^M&@C~@D>jDHuyJ!H zEr_1ubWt=qhI62Oge-aGKUuOnjSn@C!A7EH^*LC;*#)u;;{_Y2uQ9_h) zJbVud6N)G?p%_F9wvnnCSjqEy~1SHVwXyp zKnlf|L!IKLa6@cu`Ak|Rxf=``{RV?#H&{frH=viM|Av}ezsaNp(bR9;3OiEGWVq4g zYG~e=KcJ}jfTS56{KFp@9yzs4Mgmn)XtHQ|9fivO->}S$^hDWz@%`B1dZr$KvIETu z`}Le8h@p{OOIw1Kzaj};3e6U)?PN*?k=Z+V`}4b#0)G*GterxmVbpgs6~vJ#M$^E~ z56z_cQ0EZLrRu&k0kUNmj8Lco|Gcvw`ColTR5aPa)}>JvSsXjf25TB)VFWm6mRR@? zCZkUDC@L!B0PlWGk~Cv*%T2-PKpszieQ0yGmWUWEkZDwrhF z76!j~1;HvpLGY`84h!>~U{>ic864ROL6kG~nT!a!CIrql7?OKG{ z>4piB9qPOU)bEfxLC-?3C1791qBX$s!3ficz`HWkTiEG$XG- z7eFxcsbjboS)e(MHWynv4Gzwx^P@8~$dEkEtWcs0qalK6pJu44P>cZ`7!mJj6W6HR zC>$7y9V(*30N&$G1Vs-;$j~?uE<-cGtbLe_KDN!51P~h@+O0*pRq0zM?v23xWDpP(MJt{H<%yNlFX zu0k`SRG~-}+FH!`9mzSU!tna30=CpXG8r@M_$MadLM5u;xA|9+S^X7it$qU*By$bu z3NL@mC~D{j5mOxf`2jJF%LiZhCTA$fO_Bd-ARsZ5y}<}A(xLg<(VH2D%~Cc_8Al3f6D9-~v5G#AX- zh!lJ_Vdp~pTF_}bO_+=%`fU$x9M%HEQHx0WrWS}dJ+7Ry^8z$gJe%eqStCb`( z%Z;5E)o8(gZ2qsDC+KRf|f^}yTQm*GSF{cfyo zNg}yRN$kR?a1LZzH5UrMa)zX1=RzMYNGE_Cs!oRvH98lXXd;JT6p@($G(t)t3C`+J8<GPTXRd|No4z20g)}cLMio((K-bAqg@SeUKqZ2xcs;0KBAQGYH`3N5Y}o&2L&FRd zykWdfXXZu+wK>GltWoeWj*zwMvB(y_m!v-|f#oPO zl+0#j0j)X}NrH3>njvNsLxQgsQ2lv{ByddRkU(j3A&`MfX>wRLBIzqjA;a@D5{#sA z$dbXO4EyTC}8HXtHX#FqC?&VM;=NF`G&kN}M z8Cg)#7eG^9pt0pNA56N3lm^>CgVF{_&}{<)Vn33%r8#4npGYp<7HT6qMuI6@Xo-ez zByhKbb;02m3H*OSI2qlj%?=9Z`GdynXs+0M9@MuM7T}s^(8~f=KyyD3U}0KT&=z76 zVl0flJrp-3$->}LoPy|_J+#PW+B8k$#F4{esF9!pl;tDGq`6S29H%%b^Cx7YiY&4@ zik$FHVKGFBF-V^f3M0xa3fztm)6?oCtFt={kXLjs_$h z0%H-qxF^gR zrO%km0?gqh0c4TdIv7<$uShUF0G%db9hh$$U^3E#c@0c?kYr2;IqB0g&Js9tNqylI zX1UeT_`=i@LJnWR9OEQZH$EfEooIAD?5`fMA&M`!_<5X@JGqBzTKBjYgwmRe6jggc z?f3JMK;D~XPWgv1~>txmYbn6`i;^9;z`M9_Atn6wy@-V7V?R58hnX}lI^joKj_r;nnd8x15~M|Z8z`PSPSOR(p%EBI zj>oZFtg~2mEU9p58_f~h6VC)Vn(GgvjB<)(qWx*s*ttX!IBbW-`F7%e78jry7VQyJ zYYFx-l>jvKCl$2ew4j0co+Fu%bI?q1sYyj@JHXK)*dh25hsGQ(A@a}|O3-ieN&3nT zm{PwMk$~$WsRQTyy)beV186wLRYJ<}5~x4yaHp4>&;T&9{o1sV0Js1>TSbD1YtXN% zs<`-&b|APlRLw#Q)^Jf#`V{z<6A1Zh?lWavD4>pu6TQ9nTq39?0Bp?L4V#T|(n!(cwbpe?T|v^Z=P;5Xhu|vB;c)Xp1Nd(5WDrC-#+sP921{ zV`LKE3oB?jCkqp>7us$eFAMW%FRb#v1Xvi2eXv^hQdyW2`(R3!lpvYjU}$G;32rVl zybmI%EX6`El;Rd4y>t!+FK^ITWX&{g#+s^urOGpDW6V^E2{@5)2u$g2Y9zB=jT=YB z)et4d%|>YmSj^I7%J|S|2u$if^+@L2esIfrKMeWx^O%e^R%FZse2703>Jhz=WY&km z{o}eNB&ZFAsa4R505l{U25Rm$BnYtK7D5qWP}2n~NydI9HBr<;b27M07=h3z%5Gb-r%)VBsc54!FPx>ye&>B2~eT|_bol9Hhz;dT0S>}MYW#Z6~P+5WRof5x>!2tik7 zkaWo*C~$Q)3ASW&i=)dbP=@MZ(D|B6(w>JwC!ml7rH5hjQeHv=uPB-z5|4sSP}+4S zvlu&ANrKx^5VNm{as)Q!x9=g5V^G7OBj9lV0|LmQu10RSd^`fxe9*{bq|u6_&~V{T zNd_H-F=91DF?IL^GzKT!j1gd#5sxr2*H6#YzVTon z4@Jbo@}6UbBI9Wa=(ZIPANm^)7Wm;Vj3_YcB#jr@pM>;@Q9Ip{96(j#NtU>JsG;uBjlY7mn!LJ&?y96 z^;I&>4%3E#LI8^tm|j$1pdi?nm}c|P&^c=uC_nRfSO>LWKA|9o{-i)FtuG?Mz9ML) zOUj@0?DQUv#f)u!-WFV zpx{N_EKExp)Mi5;$sFwCfg1>7OS67;>&T8?#+N+v}ck8`k9bh{4WXA{=$%ny$CMkWI~2o z4E1G0S8B(2;kr2!>J!05GJ5Br7!^Je81wPMOW^zetxN^yAnQdzQg%m>R}?kh`%m_V zkco+qG8GYCVd8j7MJuy_&Vo~ZHuQm*EQquyodjxhUNQ1S%99N`ZnFq_7P82OPLrZU zf)XWOX>x(61s&*Yz1eWS)1F64opZn(mnjKmnS!hT?owXlfPMuU%Yn{$8&2NY5JA85 zP_<+`5)|2iK4Zsz(}9<@KQ=m$3V1GP2dpANU@my21gC4ljtBMLx#8Wv50d00R*rhG`b05(*k2uc>2ML{btE*cX- z18a*W=_ePUvp$IQFO2|N5xpwxfowUA;c+8y@Lgsh|( z$~e_df`DdTZbU7CAnos+$-uU~gr-N?iLy)JevAfJ;zVZcFpuTb#v9hJG6!nzC9q4XelF_*eez(G98zGLq z3MW2c7={FRdlhzLQQ{;(;(Q|Hl+U;m+fW8I8j~hvXUagaT!sX7GJMl#SzdWQ){!AA zPbkpPigFkk4JrgsKt<*7dc_#^mP5x&(?Vm{p%JfWK~apiWt;V8SP0c46%zFL7+2ua zyROD-;ERbNDRVT0;u)ExjQLnc*BrF?I*hJvQ$kN3Rb7YIUU$&wb=n4Oxh0u5@CK}d zPnMJ5=?xgO_A5xBS^;rkTS->nXa%SRxRBso1@y%RcM|lt^HGT@d3tx?b`u=i<3-96 zZo&n|TJ-cLv2Fs#*OaUJ%se$qFxt3&p*TAASUQYtMyRh%N-9mzv z7CvcIa~B+PYhyCJNa!96&B0ERS$_{sKg)VZ;NAoN!UCp&i4TyB>HxS3%N=~#^$y*A z01X*%AGWXG2T4$WAG*!{PXvGuPCh|1GPW0XponpPC1_Q2@&R0b-bOVKpcY1xq*~nsOSo)WX}8S={JpEex(4C7J};d>4iIsc8R08Xs0I zgeZ?-p==l8$I+dK;B1H}$?(>Je;KfaCd51Hpeyyk7McLRX#9d?DY0_=tYhk2$|LyX zAViT=3wi|M`JqgdO+$^3U~b$8AG+5<3u!-wGh~J)0i;ohCO;SYNZiU7KBm#wPjCpJ zV;llX$ZG_sUqE60T*$i_vSmGitK)g~Fj@8SurMd;VMA=g$HIK9he7Bdz``tTfL8Ak zXEJ;!y#W?LCn*+Yhm?R2$|UX)@}&h>XR1nR7A?moP<{=K$t=JgDv_W=NnrY&IK2_P zW>X<(IV7zjAcnf+;R_hXOqn)khV7C$q}J6&Fe|u#1l&!~%XAi#z_SS^Laj~ zMJwSMOzo%qSeTJ#(2rhjXJKqxq4jiNS(`4J8`QAh3?rUAda%0L6Q2; zp;D{%FlDebK8N~WL|M<_?aAUoLZE;=3jcG_s15X~mq~igWiWHB4Xo!~A(@&h0utyW z!KjoIj65x7poOU*fZo1?5Qsp&h2TStH<~$KZcv z+zExIe+p)p)>l&7{3}F(aaiE%03FRAOqvT>c0hlK;zbH?pg)}KfY%$T{7k@)rU-Ex z{L7n!c!jtiHyRNT`H(w$J?CRrv8Uu((2KjgW- z6Y^&(l5~x#pb#qUg#4+>EDV1a41i))CIgqt9S6+koy91NqMnaB)Fh_Cz7jBUr zs2STvQo*tZO0C>Xf+w2=CD7#_$X~FP$?&1c9th=Z|LF|9u;{GcOM>xU*mLIgf{CPk zOvV!P4q*Z+iVqd$LjHYVR5*;Juk^tXZ8=B+tRLpK?xQ4#7=YgKH(C(BQ0<4#_$GQL zEr-I)plLq#Lj^X(%#;Zu4@tTtvKs&yiet*GF$F||xkwO(&JoDZ`36>(m5vgFK(jj_cRs6`5x-jaGM0{-otuLts%e$Z1z2p)cgQ@kKGSQ5c>hP zY2P1`;Kv6z(tJm{gK&O|X(u>3I@b;zvSbh<>)3%7e+2iZ2I0mm5Sf338yv4Lw0H=# zNd@iJxnNbWQA)_OUDkwZH^ z!>QvV%KA)mq?nD##xZCLi{(t37p-3|L?ym0nw~FBzJRkwY?%tiSiKh$ zz=uOVLY%1a3v{}lu$VDz1I_rxe%i?5uV5s4BmANO3QyfAB#2@Zpv4jiI&U*cKl%y* zjom?l%pF1kNJkU57I)gf_;A41k@GflFZ8qn2<_gloIh! z`3XnHvLYgS(&*q%aOiC@2^xPw@nU5pnDq-vo(JnCp$32p9VD2DYfOd{b^U@CSAd~Q z=*Uz;8<^b`;zp03Lm-z;f&+Y&q%3R_hL9o*>uE(e$lVs=C8rwhDNq!zX3F@GZnY2> zvYmpSqS8RpC#RsVOEi(7cM7_e1uVjZG2P$bbHEGK_Xlbo^P4u0;)m}3hF44WNZ}78 ziYW3AZ5?G7>iq+A*!x~WQ4MYU3)9Rl*v1o}8UVa-82bwfDIXYIau8h)qYjaOx6l`1 zlAn+Wh3<^a86%4gWT$hZ;}p6%mI~vZaD>5pq|mJ>{YVd^ufm!!beEkz3w^+ZWynGF z6r;n(_FN<_z)rWpiny5o#s;^rIH{P&PN%_4R>Mx;jG6Hv3NKwA{pElX9XaUwn6Ll~ zqbmR(aJzHEmvr|z!1`g>?N4hPVSngMz>U^((oL`txDjU>6P^X%tTu7dHL!1LBrT*a ztVnn;-OKH`z+#jJDa+IlmO|&aKzofA!6=|WEx0)NO)y$IOok7w=7!jf>oOT$#Kj4# zP8~NGqt7GhL1QRdm3mSL7mI{h4e{NPatP6x7CGcsU7ye-dz? zKW&2#8SW9Lq02(x*VJAX`mYe(3_AdK{Y=G-5U3>Mb?Q-J=w~p!3e$bDlLye47*rJaoivReqK32 z(xd6n?D-<}`PeJ?0G6-~j0h4Gh0@>~ItH^wln$4^@XaeBz9LFrfTfmAgEG+l)ee5B zi-FOr*Gc-(br=xa#lS=yT;LM9u8GkXP*TyT7~KPVTZKx+>1v4kmas6nO->evO6#I4 z;!tVtJ46l@v`_+^zk8nmvrxPQ-2hwih_ux!L7#^;JSIVrBpmY0CFyq9=Xxe%iWxPM zU_~P|IAiCaBn1xcd`i+DQecAKN`fl{`1+g#yluilWSA7CAwwB_f=Br8CJhmiZ%2`I zx-2S{rW<0ER|J6HA>knD>?A=T4w9?gBxu6HZcGmev}hn%-$#OoJ{S}5)hE2=qS56r z-2sw@-H{Q-_m%+AdEW~2k+ZQc9isCNMbPQ%DK)5%k`&V>0yZnB$k3Qhsz?79!j5i-qoxr7vKA4Ik(0aZ+Uwe3manyfB|0 zBu;X48v8u>_6&rYC{>QG!CnV%A{eSYJXB#q6+YYMr&8gk=;VL7kw4+CgQ2l-7JV`N zzB7Cl-IqPlb(*~B`d;EBm&9|N^ zh60X_i?ZkXmr6zC4@Wt;vX3AA02uFL*#EBq#GD^(wj zzl1#fijc=*H-pkdb7s?x+1CV3qp%=w{}m2_X1HHE8&o&!r6S5a_<vWQl{Im?~7rj;$xuE z;FFkXcOq55ox`#JqalDEsz4?G#{c7O*;P(ak-{meE{a!$R(+hrK*0)eTOLU zs)4O?_|^-w)RBW4bdyJ^(`YyqqQLm=%hHS)?dOs)tr3<%6-A%aAs!~`USqqf&MHCiXcu7^EDUuK^*}d<<{lAOGJ3X`w779;J}VRzzBqNQ$C_ zq@=R6OSU%J^qxD{ZyNu%&*%0y-*cXG&U2pgtoKe+M_^$`ppdgYHxG@AOMr_j-0HB9 z1{P*@*yJ%5Zj~lXQ6dUmiY8HbP;{ZFI7B&4Axd@bLRR^R$B$K-@innZUV%tf8A~k{ zA*$)g8WQ4uveBYM`9>{Kh=4<8vEZ|_R$~OrV^Yhi)nNLTRhG<_W8wELuCVAmbM~-G zfw|4B@~L$Mt8|$^U6N22wvy#)=1O&fs#~c=6eBB*h(gWH9Eyr{ZVz|}@^HUCy3x#_ zrEOkKBk0K0O9*!3>Sx?UdB*1*QKl&u=%+dR3rvYlTAQB(A*1L&%<_&NaEMhWJ8&b* z8(L5(VWJ{>iyn)pqEW@bbRxY*&#v*^{q{YR0R+#OwVzG9_ zo??~qd&H=OD!oH%SoGoKES5^0)bFfT%t*H<*jv+gv)E%Ol*Qh7>=Hqzh2GJZSQ{MV zAFy8czwQ-)?yXpNVwff8n%yKo$SD`hC)D^CEN7{?QFNV;pd-radBq3^b0pk8@1$~Z z*+_A5>7`k(o|YDJg%Kla=6_LWQHHaav-I0eo;sQUmT*d?Pe3^SB6a2F{&nF;gr1#T zyxyO?Q`%$mDYtVaPgWH@x=mYA&Ks|aAN0Mv>RiXh%NvKEXFvM&WTNN6yUumWi__M; z+xeyYZ}iw$w@Kv3Bz`AKrGq9dS8QiunT(>wyyX_(eRE_7(?VBs?e&e(PE2X4oD)0k z6Sa43rFBCRrSO$%V#>_%1zaY5{)`- zlww<6Z8eyqSSuN29a6olL54dsv1*;1kT))p&{(yXZ_SZVCoaRXg}17AE362~$z8Kz zM9Mlv-Bj~+X6vh6aaKC77sPOVDO+eeJC=8MwvhL!+|?9MopB4L*SEMb@;n407u{O9 zSEE4E;(V_dZ-JCWaqlLY!m^Rd-4|v?%)6CFt5JTi!|s-eltoD|gSTht$obvxC8IoU zeKGJ#9hIl9JwE%@@pB6|onsmmtlqt9{qgIo(^};ghO0=u-H&$wx9U1q`}95^EWN|u;gT;J5}Q2)lDZ?sl3G#?rm%i*jhg= z&c@|*$Kw}AOYAGB$>cxEaoFI$N#$eLzL;mL+JYOttnzbrwMj3lexxUS)oz|w<+juD zzwwz%O5b-d^J{d{1D_1q-g2H-)}0uTki-x+O#2a(Wj)-&i0haa{dCdCF!_4B2>XRi z->RS8zJB-nh&R*js-60W$Ko1JIW=$hy&K%|poISO)5qRbqjT3@JEONP`P{Li8i$iq z4tMH}|}4pt?LseWIQJQ^C<2VbLqE1Ti`S0ePy*BUmAU5|W8n3*xKA}hb#q|H%Ovj4XH7l3beVbAJ(OSjT@T#b-?e)o%zsiVb-!+pQRHTNg3Wj5=bSd>*-FYHq|RQi4YW6%1_8~i0#J~AzEOxbT> zyU*V5_uP8X(dpEKe|u)jDEuf-4DYp*vbyEu_uHYqWmJ%HbNT4Z8~LxEjtj3n|LW@a z$wNKo#<{(aUTKUjc6mk9)=tK6m-?KM_4}%W%O7sro*ke$vHPaK_HvIE^PW0L#oX?3 z{muP%`Ka!1kGdb+dsd$`5DyJKlI*UK(jNAd=JF*q@o(=%9B(N56#F;K zUp38VFl3%~hP;8N+R;m|Y!8aHFK{f3NUPuH-r<;Zs%xKATkG|heGRRjfBxL(Xx4Z8 zz>8~|&gm)vM>XH}ZKT@oJBI1cY;>+ax#+b2m8V^{YG1DUp4r)NUSiYosZ^nVNZ9xK zE#qyry4gM#1K((FxH3@R^ThKYW%<>QSEQQGd>dhi=p=l*GW0=5VrA3%$i=)C7Y%wh zGZvhdlH%fiuIlOQkq{qrA?9LIvdGKsD{;Y_&aY11bf@cT$EAQ9S0u9b@9mn__iAhI z#|KMZhM9=+&*CZAvFYxPy%DtO4(hEUz}VSvrfRH zgjuqAs43p>S#{T2&rfY1c7L+z+uxmZ?a9N7x*tEvuYdl&Na#MgdWlQW;*=P-@fAY;lhZL!N|8~AH-xAuh?po?^rpWr7i$9Ep_ef?5sWsd;Q~jB=xG&E9 zM#he2{MPn|i-IJtgan>N)Qv6sZYjuGq_sQl#f1%zop?Ln)cBlWk!);> zvX7EisCG=^)#VX-&V{c&+>rbboAAedZ2M^T@HUr%7?+m^Gv7DwHTycpKGd%x{e)SH z+k^S(d(t+BMX2^K9yXB4y0d=nlOMO7#?^0rkBgcpKl^<`sSu+_S$pEyev9N-KR-3)botwb68EMzTE*?Y7$g~FM*YEaG)OX3@ zdwy1(q_jxJ=UW{Yb0h5cT)Zn^_i5|=`#Vql*#DHKzW?xz+t~?fsSTbxJWPF66Ms19 zV<)#YEpfQxS}8DmTkcasR7@1t{ZQc*ee*kGs~s|;9rg@_SO(n*ec_;UwO1vm{&r>a zR&S~4&hfumlX+fRNQY0Srj=$L;4W*mPEb45YZ+2$x87e)+g8UYwJ=VRC+5A#(2K@n zbXrfX9HVNTr)v5k4}$^6dA5xa7aWXK8N=@ff;=6wrwP8B|2c4Zyi|3jM=VS~G7HSNA1^?5~(*4X09P8*|^4x~xVaqmxao#Q^3HrqPcC+Y5w z%@dy0PEUTWJL!Z+UF=p19&6;Yj`?Y~&LsbHq#9N!sA_ueylK4NbVJ3lT=6l3t;r)w zW(}*VbH;US|4=$VH0W5|xnWixWtPMoQQ!JT|3&iM#(wHhl=#9?p)bAe)3RTG`VxWb zj*QvdNJQgCzYM%?&x|;k(;FQ+J1wDI{oSdEU9!x@YWh}*Mb;AQ-}zek*&qESzB;O` z>_g0yjorJO39Nl#=$(1Q2JZ459@ajus-DK$q29e$%uDX~^wHo8*!-40B=&z5l@C)0 zykha=Bx2*2*4edKgxL4xy|}p~9OL3z$eUK?qnf7EEmGn8{1|I%`RC{36R@g?(dUEMJu9Hfy-JxwyLc(sITY#VmieRKkUBX~H<7Cq$o1)yY-27swQ= zQ<%#m7%h-tqooj)C1ld)dnBQv_p`>X*qZS?zp^HNtJ;){pUjWNyZJHdmpg{HRKF~6 z(mgh8RkMq`?0~$~pUlAqxuI>Rof6H?oP8^}x~AK;@i_9e&h|TVxzLw-f9d%J<#;_l z|4d*^y4?$Zw|nkki^opnmC3Kv?aCk8a{5T)1Koiuu4SIpeT7z?qjqLJ50+jEa6OoJ zCv`~jWys_3Xq&_O`>TxXm#^N}v7|hCQ)Y|C_L@^UZpk5gT~&{I&1>A5-zZ=3A)V1_ z`0A2!aotN_0k!oajH9au4j6uYzaZV}yC!dtl@ZM^W;Wx2d%nw@S%Jzud*;_$N{ifn z*R#~1#IC+j!R%+v_9pIKckI(8<6WeK1q_?kgtl*O{P@lCd(x^@N2!Mjk+bjqzE@!X z>Gln~Fj1p@&#$c9`iEJ3L|JE(@NrvH@nB1{t)tyVk@qVcYt&TIBA9=_CWLO>AbTra z{fW^X{ahdV{1|-S;nvjpeft~(12S!w-d6Q|qNlogIG{5_t-Z1(^-s!#zQgC~PBHEh zJEmu!zo>p<*2#c`sAj!3<@<3*XK@u!PxN={Tw&g z5B=&~XKi;xsZ)RV$!RGA+s+x~>f03@=}KDB<-X&MygC1&asJbr{-nu~9 zc+MravVgo4Ec6MwDV|9u!^{`Z*T-(4f}v6hu$ z^8~-|8r4~ZD$6ZA(Maw7Y|-*F(zy1`I)Q?aY2}5$V;b#;H!oc5bS~qB`l0FhC1%G1Kl3K ze0ufolzYRgb~f!kdz3nUF*0uL%ouC;{L*tzV$Z()!eg5I=CPQg2a8$59|q;6ZurLGI156u0VG_O1Gk`|aw2Z*r49CCli{+oZ3YzVF-srBb}q$F^=}<->ZHLn{N?+tjrA;`qL=4wH98cQ463 zEwt1Qc|(;@ZoPulsV|G0TRxlT`ijAWbGNV9ZudW4Zq^d+gWB&^B9CEdHe1 zsF-$MZNGv{^LSI~pOmV$sw*Fy^^=cz#W>E8OD_#@TU_9pwPTao_NT?WUe0R#YuM0nw;iF>74ksXUNuW!s;<)3iFr|5=U zVUtgL?+mM;&QhDS{7XSyAJ;y%ZwMlxQIpPSWhF-Wvb zH;9p%IbAK&(#5y&%?*3Y_D6@#*FOAiJ^cMc;^B0`x;-g&m4iI;6=xnVDvDYsYJ{YB zB*oFjE1$PMxGT(GcabARRAI8aLNOym!fwMLafK8x|h2je8jrafNGWXZoy}i_X+5OnbmTUVrj~ z<@n8o>6L~lwbORb&o(tqY1KM%X@ybBh}OmpGlov@Sn^5d-Wm7u=8ALgW~c;T9FpLB zW|`9EK5OK=&0|N&hMx&XX75Ugj95b1`|!YF+c$#o0UOk3K9P}P9!wl~A97)vPSAy) zo=d~mW|z9mxf&Dv?3%V8uR+Rh-2wSkL5teueBb5<`W^UuD(Ua+O9|XN@7~u{8=%ZS z5L9q<@J#&W)5niUoVqhBPonul{@1}%>0aA>6#uxl=`uuKYbASQcSEu(XUgWH4=UA$ z1)}y= z&v{rz;r^M%eaAP{A3E^Ls4eNKjbgXtp9p)QzRmi{;dfMT%ruDTnOXc~UZ3Q_#P#ya z!?0#wS%V+F)9=SMZzvR**eg%jW^ypUHKQxlB=CIjxAty@&*jc<1ux|soOSI?<#1$9 zjP$8_Co6iDH%?W(+5Vy zo{j0-{91NBJg4n)rA_(73118Qn^&%CB(KrFHm5PK;FBwtYxDMw?H%jBZtWf%usPbG zw>j|C^1GTiuF48H zlE1h=?&d1IYu4t9#U7fDqFu8r9|fteYyax3p4Pn1aB%41Y{M++l#KcH5;v@EZt$M! zx)ipIw?y45RteM8REX%K6y{=0qS3+rVTR8h969r{C%9*4&##)le|Pr$sJS-$*4&BP zEe_4=j14b~P&*jDw>4&8IRB`Er{bAc-vVFOJ`oPAHaRfX_s8=$mxtoIf%$>anI+6; z*Aq%oLSCovjq1O6P@ht6Bq$FznEZ1e;b`DP8HigFJ9|*d0n^CdG&|&6_;5&60#VSZQ z*qveg)$1kAT=+I~^X22I)ELVkLmj4Q|16=aSN&dzJy-dP6}L9TFQKZ+56{k}Gq(s%5F6r~N+no|cWhzK83>tM#pN6Sc9$ z_5A0Pb>e>5T<=O`RuhWR#NY*n-hh%>D%SjxJ9h;tT?(rL~_eqvCAUTRdj(I%0GWz7!gRjR|9?v*F z>-JD-p<=apgzM7{8qKTJoV&^j7v=_@?k;!~WxK&k_o2#8*V7)SzR?R4KIp5qotDMX z>h;Hra@(?3&G|96@O|!CRoBydcBqBLh~%vvTxmevbUOQt^7poR0|7=-^3|Kwo2nmM zWVAY7&Mj_uZgJH;KV{>wFHa(~c3f#Y-1RZ#4L|I%p|c5KY--w0bqxF++IiVa2rpXGg zpPg5cnHby8rySCEtYW#!H|xtDS6d8E#uVJyZ?dL0&5l=9dYNNI&9!Up-fzcW%kP{w zZki#tQQ_3afbWtS&-NB(>-&E6Pg=P=EY9&)dW^MAgP7-x*P7BRDsW;O{&3}8co=9$ExNN)MnGi(%n>wl`a=)`V+fpn0wXdj0mD_KL{k;BFn`(jw3OzjS z{f~%G)PMb(U;SV!bBTIUWme%j3(;x;H?uq5aqg#QzRaqQSS@xUOF!}H+mKBU-#xI4 zux>awo^r_Km7~GLK`#ckMTMqdl8xLSOgqhMecaxd2{WU2p5uKRMCSE}%YE0$*w(J8 zKl8NPb)O}@uDxKOcXz>BPPJWi<;IuRBomq9cwwYy0b5-_|Oh#`x?E5en}r ztHV!@Hflr*#4~5ie|VZI_hBi&>+LhL?~{IsoSk`cOH4|3*#}KY)8O9=)p@1g*RIHR zw>?eWw#@xl+SR5Lo>$fxgbP%^d-?5Ba6_Trh9c9mAH|*~cgOtM_+Xdc*t0Khbh;w$ z20z%(W4Xa0+p+H9*D$lsZ+bP*i(9@5(TvM&;T}eRG)ABGgdF{~C?lky;#=6tg`O|_ zH#UV_$^Y#?ptEwBSNXRkE5|B#pmX6>J5tVR96mgUfA=!I#`{Iv_P#X|M33qyG?XPoTK%|(~yYAHsj z<#%r1iVxRmCGQH8-nyjsMMGMq#QFMj`}D)l4A>n#5+(HeK&E5MezA{cF_9l@EWY_x zIs6sF3NGBWoZE-lo629ST@h~JN6UM~<7Ig$(r@7xIps&W`xgi}MMS)@aJnJe61mGF zM&-{L-IiG0mdDdZEo^=UtWhYDO$oMWIkM~F{)OH*b)8%fM|dgy$u!HP_VuK(#`nLTX(H(o--{<`R;CyyW8=ha>WkMgYr)|S(Khl z9+;PMu7AZnvCn+cqNl%AT2}G#UT=~Qn_glRb4Sxbro>I@iFdl&!2^{7zwYdi^_4Kl z6W)_|vPRzc{r)+N_E;R4xw&-ukjlDG3F?sw3~I1|vy|oem*p2!1yU^Ujj7p`?dG&SbUwdKqgmJ8IjHfx-J>342>6)k9O8}H%;E*jS@J&HABet5dZ z59Rr8^Q=k;5^Wp&cDCwgdjFG@Q&lHEd>4BuwYI;QyOQte^=&?=^n`I#fKSax_LVI+ z>UnQ=$aos)k35gMwbmeAH1p$yinq`E)ngxdYxuVX2CB4Zo@h|sxRV)Fa6|mJRfZu2 z-=Aqffd_+!8y+5bc;VrLhaVmRc&PBu;1PsJ2p(a0MBovHhYpVzJmT<3z#|Ed6g<-K z$iO3eHPe8hm$8jruh) zTnQZf*CWcICWa|ds^4c=5T*Zp25~)yO71g=_s8hxeZ~r+bngY{f*wE+fGB!EwuIWu z*h0|J&5Tf@9BF1OW5wg+Ck7MwJS0PP`XOUI!4+y@Y$M9uEsRK_{4+^!ZDs6a)ox`Z z5@l2yBc3R+M`U^65hL;6%W!n6ogszv+R5e~ZzpAx9+Nt=9+RGkbTBp(I-)xmn~3sb z2iX@3pOEyWC#0O(Q$`TMS9lK1t9Z&VCWwJa(4&)VCNxV9J?&(e5KQ_rMj%n{ddBc2 z%2&@A8(Fs?|K5b7Rb6C{p6_DFVZU#t=@)3EDb~s(`g4X5QHQXG?Z1;2cSlo`f=O}{ zA6F1>-(75tyN?-^!4`f39#eS!`*$YpJ|V7-QsHhE)jekrA2py(LQh*go00aXUJ_Zn zAdT3)0Orek|1sr=3PejN2}tQBLvyCH{Z!NMlS~RN;TGqJ5Eqy6e|Dif6Zep)V53C% z*S2Vvvn3xF*9T!Pu31xr);vbaFBuxB^d*Bqm}-0p=7+k{e7bf2pQ(SB$ME666fI`R zx|^|_Wr_pm@Q2PdXf4qVT20YlH`&l%-C$`wfz3l6JtP*;1K7&GG?zX*^zbdtih2)$ z>Ah#wHR@$dBfKQi8Y}2eJJqi(#2F4$Mlgm5h8FtS%TW9;dYI)Wz^0|?4e^UijUWo? zgDSgOY*g0An8s?wc2OaT$iu}oo1;l*;v|PA72!zd73sCbE6|WK@}B{;=M_Vl zJ)S5kNclCxkkxEOqAxPd3@WZuxVXyU>U-W4)msQj7nV@qjor6zfY4y=6<24#Y_mIxo;TaEVXV5yCY|T+N;pCMN?`BpwKsrl|;Cj z-au>eesd@gMrv;v(ge@yE%3}H{^OyPw~Xm5#b+`D1FJxB3HUqJl@`?Ymf_42nl8}3 zlW5dU5VD8Dx`maIiZuELeJyppXrs{BTmzP;bKbgYgu?K?ijzn4|8$*+ zJBoZhFo?@mR0OK9RZO;{@@VlNh7hazznj(nZRj4P-_LMmIs3oI|9>`SYp|8lh+A2H z^sJwuNAX0oj|>a$1Oo~>?1QPG%^w+axVt$hNhD`V5kX%+GBhdHNO6Fnj}!(N0?2KE zp##&${sD$LcG(cQj51`=ivflv*3TklAe~P@%$$Wrd2lrpM-V}i#Be!m zE=3TT4FbYvL{v~mBO??(ltv)VEJOzl62x&9p@!xTG4!!FB#|ME^P-#~;A$C@)`sbT zj1kB-W74yhRTw{-H_XuFzF_>XrL4Azqie&AS=?t${s)&rmLs6S&YaL-fU-uQp*eF% zLez@FMCV5sbYwKjz$qQbd6cmh+q#s+O^?QDXmBY-3VDA43F*%uk&W~}Gqz)%E6Mr~ zR#GI;;Ac?3(49o=zraS}o+nAve1XL$eho>ee+A;X@1)pTNUIZHp<;|5i46Ne?+EeX zbR_$YfnzxvNLVz0B1_s&Cg4kfWMo!H=3yRLBvG415l3@=gFkM+z@N9LNf;7H1|9s%kVh>9 z98ksqYy5^lCYG}ib#(1FglpC%HX@HS{xIyY(JO334pshvEzr?xY(y9-Ou&d-dy|du zqn4Wx((@CbjCO~FS!qlA%b1VF*0T{Q!ZQ=h{4N_&M-Eh+o<1GNF~ue}Du_~=D01mZ zxF**5m_W&-Pk)ck!;W;Z0U@-8g3rNDKj%Qa-$52AzMu%Bo4+77KPjMj=bQZaFb(|~popPo1W#+|e|ht{aU(2ogbizKZ z?-V&Sdjj0);K6aqV>H5pugCg-6C%bag%>x$C=(I)4d52Oa-Qkwn_OU?q_c ztX!a=Q(`b-#PZ_&XbC_3_nZ%(j~Vk!g)OiLd{Yr2)W8omdIkO$HWR@0F>XN;hIxY@ z1q))@Xa^5d2+jS<;63*=&sCMHI+$241RB~@{$mND(?a+xEO5qufDNXg&iWfUi{LV7uQ0@++d7v3w9w1B(1fuckT%j{kT$wVUkneT+(NlxxIf0dh!onq2&17n;t=ya4kR+@ zfHBblt^WdeOB}4~IiXV$xHh6m;09Q;GePK}KndKC@&e^b;2SWyE9#TN6;bR8SPb+e zaXrd(NIXIjB9Q1X5F9w zl*`2B(SQstLQzLQWgue9y@;mEA}3j>nmS3;VoV;CBMX}EO(J@xqEz%r7T3Ud){qs- z{6s~NB?Dw^Cz04#Q697x5Xvr8#=sX-Dv1I|N}hBYQosQpV*wdHbOE#pXl#}@sVjFn zQxIJzkgbzQunJQY2{Qq?GKn}P(0S1c0vVn})?B6Yqf>xTG|>YljMAk(L`;m4xg0)= zqKZP~@O9W?KLTTgMgZ0NL7?U3L5I5kRG0_tlgG6&w*V4`*zuv}08*NcXy83&w2_0i zS^*N|yHNrD!JNg$m(=-EI;P;qT13Fj%|##q1}lK4sx zKlhVF$RRN7pajE0_7EEpMve1{0iQZ0Il@t^6221aNh9SvV>&K?oTfpI)VzPdNFK!E z`ZS1~e*S-`1$MCHzrO{L_jDML=H>r@n&~j>mtFb?&@aPy6Fdo)^;N*T(#ro>d}y-@ z%qvT3{{iP~LAF^1>?xdQ;7hS%uLv%VYG%MNka>s7)o>-mRD)LVeI$u+HQbc4 z9+j!#ZkWOsQabDlMn~Z)pzFu?DdB7UP6V5Ql*TYI^lOBeLkK^QtAn4vf0DcwbueY} zmn7&~xFFKgfC+w_8{N`|>z&lU7!@UJKqv-j9Eg)3w>gqt&aj7T5Wsj(t&ZLvXn%0ba5(@^}xl+I5JjEG1u?TmYR);__7Hq3ijpZM<4z|{Bw12 z1q=m{yx{`gE!(i6_ji&FF;0dlso5kB;1E7VlTfH?E( zLtpL>XY-`UabyxT#WnsYQeX|hC}|JWt0d|zh-KH~MPKwGLca0nupzF1YT`jq+Xw^$ z3_!5t00~nQxTR3FA;9+t_;xA@D;@@SL<}Kz+m4b*>rseir2zAe-;eGCwT-h4SCN3yW5IL;`%IT>YQ?dn2vJFA<4iAP3-b@5{WVbwr34VRM!we z@c1vQ$Be+E*9|1k*cf(_b*&_E%ou9@>LdxzXW&^?Bh)JMgtL>h3C^I%BRvxsPY=5Z z5hbM613Q#j6R^AT4bdDXDtp5%hDwh@bJR`2%FBK>%!|xF0*}=fd_&xvE9DcEYYH2~ zy`$)qDKuKm47b8UzLCU(ZxCNN-Hm>jKiIFOV%FuPyTXCpG?5+!T}RUg2? zbW*Jt`cZ^Ski%~?!Mi%2 zJebD5Z6~?>^P$h9c9KNbP97R6GM=2PXuEkh=c=waQmAG=#9u0rB%~JLv*FC(ya4y6 z#Gvv8kO~)J$t0YhpWu;4!TTWmscRsOSK2@t!zK&9-o-Ltja&d-{?-QOag}@`Etn`e zADWS~7J9?S7Q!Z1Ov0JAFix6FNg|;FV#u=)VyIWaMr2XILTJ3;RT3#%2+Ku$6+z(W zMHLTRkJp1z!$qJ}_!bG%7sDd6c@gMAcR7&iMbPOM&1_^2cJL7@UyN&_9gA@zSS-pG zzjqVFbadPfdSv_+N&K~gQQ+2368`qMAr>`A5;gYV+^-RmP;dYR zMPErG+5v29|0IdzpFASyw+pyE<^XQL`$NLUjxZ6`3n2X^U~vYOSDakQDjY#3Pl$k3 z5RWjxteuL~5`e#m6R;Ph3#BfB1UiTlB#!2~K$i$P!NGB^0ta$ZfmaeK5+fqn2`Y~$ zbMPFe@xs*Y1d)EAIu#Z`5>AkZj?PdeM1zCZtidZrsw*ORGTI!xH_i~S2YPJ80@Im= z4ljd5IOakOG!uf5LnAKGx`vmI?1{aDp(`}Uz?XxUXzO&ABydnc~|`tE{DqxS@lcP9r=X(eP}=`Ie08Uyx{ zS3(0_cXPmHyLp9>(i(6hWB(L4{P$0l;zK67xCCpPyx0xQX(Y4xQYhL36r3jDpi~m> zIm*kAdfXtv4;*D9lH@An<_>}{Gube-@EETk%5ewhJWi7E8+Uv$W)2H55&cE0V3Kmr zCyBCrUU>xHOKDr^;Dh=(Jz`9cRw2zLxKJOWsT|Q zDcvRTnJpzx_Gkat6oG4Fq=2?JZpEF)#h2d4r$q{$^Tu&*RXzfdL$Q2(vP5+0NXQ3Z zHyR1I()p-pi4Q)DyIGix2%}OT+=P2OosGb9=8J1``!PtQmca+}I*}V`zMxE0jtz^T zE??Y~+f$W5aHP8ypTm7xgCu@y@JSI1fhPA?Z4z(sqQM8J#eDqe zm><57qKNwZ@HO1u7yaW*N3s6k&^3pD5I;&;4{AM6!T=oc2a}r1{vUJpdR(77!s~x< zOYR20Nl4KjEU#3C2uW-J6_m{^oQdo=;PWXfQOX8bZ(ylT-2i(lu>gDlc4!Ad$fNf= z_!QA_08~6302S+^SQT{%NRzuFW>SrCET0-V0S9dasn|XLa4Nd65ns&hvVRgfw;!Tz z=?n_Z;g*3rIAIcROyH9s@qvSUoReA=D&K@}rYuE@fp{QyPbwceoD2z69EjUeqS0s| z?#rzO+d>v7x*0AHlM!?UD;th&1`GF&vn;^bFAFT>=z-95%8-s5S&wfENfoA-ESd>n`dI zffaXcC`=93_X$D?<=lrb9^3+6sJ8HNPV3(uk^=Hupb7Eqlj^r^!L7MxKAofvJOw+% zX&t6ncxkc)c1$;s*jC(!yW{PoNZM8yzFGZ~)ObIi2$??i!&BPK9G;YL*oH5FHw1^b zL3eEUJ_*);hd{8LG~Esn|NdhV-?|-?%T7#E+b5u3{wP7K^|}amwu3uuNGuE%&m$-_ z42~lfRCG8J=C|7Ke7xvm7;cSq3XzDOFuy!frxC+09L|$9bPmA_;V=Pzl_Zf?C4L^{ zEXB`klZcZmzZ8+FbhH+#V$PlftcbFsacjy()Ef=6LdgaKQ$Pwq{EA5X;D0B6vFDD77j)s4s`UKkRFa=^CsISyL(DtKg5v& zv9X{jXfHu9(cQiLBIGLnITnNj@{7H2B%2Tq*IU<7CS+7@g6YIc7}wt&hiTqHwT)S zV-blI7D2~O4ksS;g%Cb+fn*I{fRJ0ngK*>(HbO%w@nFaEI^i>pdg9?_M_V=7m6m&9 zubfp!66t$kKT>;#B!>6mi?F@PvPH@IEErPFU9j2hxoR@FUB=pe{HO8oe7sVyO_n zk-c!p0-hvlCSX0jsW3lMI0#|Ph94(!O7o-t93yWYm=Xegz7m?9tr3oPNsW`N0ggg*(IeoL8zEtBvi*j80GA&R?DRUD68aku_|H&mo`(GQgVJUK*+Mf&t_RJ+=dI~I&caq^q8f(i& z%(4E(B(XjPVwJOmB*vBqOeY7+w-gvG(-A!tju+=#39bSJq4M9lwlZ3(%$h#vONh0P59C}Pb2m(hbArLFY3Yf%Mm$H;JaJPFaVT6H< z(_k~=5=jz;kpeQvISoeS4MHY)7YV=J1)+qt!~3M&QzG;(juf!mEg+5rm;JZG6vqp2 z9^oS6NvYO&0oK))CiX3XL>v+YB*;#bP6vCvNhJIy1@drCvH%~l8wH~q2wr{)$vc^j z&!g->z3K4oN$4c%ONY72F9T*|o>L^T`jh~ZoVb|zQ=A<*OA5#%NH)u2lE^3q&*8e9 zju;oFNcWeL0#=#8>qZcyR~2l;6;r*&Cg`Yl6Lk5pEZ9GGXM(GgY7XAUYRFhtNS%%W zucU4&PZAX$g8{wj9tSLN9HuCN2OP+96I_~gVmovkbnI>+SuxKbarLs`g~f0S#Omd7 zNX~hWr}E6O8PC`VgSfxe#N=PH5ef7o3(Q;hu@OF$+b1A`JWhb%sW<=NjJIIyuRa80 zU|>q1ss{cEA^a1J64tqic@jKT9VU6Zh9QA^{h{&}0(SXIz&I-U3UkVhlVIuc7>Njv zgB6i%K$iX@k>X#V(ThMnPmstjj7meL*)YIPV<_}AnmYqlzK>+y9M*#vJe{L73$A3RA@qJr^{M(n(~I7*&*fx?C8~gIXC@1PmXso`$yySt#T*T+?lJAVnWIK(kux zp~=sksGKwHIVV!U{0to89hZ?r{xWD5^EgPCp8>_#N)q;13GR%a0e7-ik%-k<*!l!{ zkwoTMP_f&WAaFEv7RHgydN#q29P(j065fp33W1%S53(xoj*uXtLaD-&uZ2osSrRXR zuLE@9Eg`{MSOD){O~OecB^(4<=ctPX;8#dA34bVn5#A6-5b|hlAxw0<@g(6L4-JW_ zf`(iMWt0lkS_u1%Vt9Q>i1H>uP*^YB4yIB$4?P|zwg_L2nIA`SMX+^*t6qIfE{~|h zL<@`IqVLvOlECvpf5|z}f2A1ohoQD&sAo_@au1eJMUeA3h?jghiJ)_E9d`6GNeo`5 z3ZlORd&xBegyVtamPYLDI_ z1^DWz4Duj0Py)ePagT&mN+I$c_enzU0eE<@6bzcR5QsABEX7SI!H9kVc5QCG1g3_n zd#Nzv>Ow0EFMuYe4f09H_IZTF& z%E5(~6KrG-HXS}Tses;|TMqNp?mci3##)QyE`m81D#T!@5= zFTx$zAbd1J)EB6L;o%G4eN?~-StCgkBEDFlqrJeRw4mGySU-=*5nLu3kfYJb5iwJV z#yKK>DWdYrpey(icv&=KlF+2_qX(DZPFzNljli3!%MiLqZ30n55tku!?x^fC?v62x zNKEqzoB*h1B;jvH6CrLG$Su!+#T2tu7K9KJbzXsFK4DD~I#=<9n3@eq#M;nsVjhR} z_bSAtcrgioxe67u97$qvCF}~iT?hh4g_V#zj&39&a1CDA79s0vFaVZ%lbFbLI2Tu4 zg8?(kkBwMiZ#IyGMF3409U@-7?Sl^x;9~sLb;yeA!6a9z3bOG>C`klXK_~leCyDFZ zX=3CZ|GO%v7l$Y}z-UZ7$(6eSAL~WkfZSPmh(wgC;cf5Z8!%^grLmED*sEh~LJ%cX zLvU}PTh+KXmJeqEqJ0x*Xfo)74*0jO1_BaaNWw1)X){o54fKp&DJs7Of(J@zvc&r% z_&%bXL>6A8Ns?3Nftye@6^;jlV9iaK&xEg&L{Kdxqe3m56&BR6kvW)r9h;z{U3D}n zvOfbZe5?gM&GjTt=@v{99Ze(=d<&lo^KscN$Uf5!0-J{P>R>Xw`pUCJyB`So-{mNMijT@1hRE<`Q)FO3hr(Gip&BVpVCyg#tkvUwi-g3#p+;N(eoJ9rny%FMfv1Z@qFxhuul z$O6hv6ml0v&rMi52`M?IpfG8V{~qX!Rv_Un1yJX357e!kMk44Q^xI=qg22)6J$NtX z3QOo+h>vq4ZjbHMA_!S@xe?dn-ozt>ig|=oGFqS=a!sJujt_n<0kSbPAwlHX1etkL zfQ<;DOHI&M>NGYYh4A}eTU&@k*4&4A;<_YB49kLwoA+^j_^xX7K6H4dESmur=ntS? zHqJ(92;Rl>kt^C`6(P=9=!^;}^-D!a8fiB}y>3+kQ9!e22uYv`B_^2+$D5%6Ni#`S z|4gvnLkJI;k%-1a+!#Ju^nM7g%&;Y~7Z2f()47l&>{?*-+c}X$poBHV@K&>uo3+k=frqH!grIBQ$FsSRAT@ebiOubhnZocI zg;2XW6vD*X8GLSs3a7S^u-;?Xi0N-52xXMI4Pq_uZSr0BwfrgZPJs6gk6Ciu`;2SktO5*y(~ZciXq{mlfzKyx2L z=QY6(QCN{#)GEZe?T|%%PhhnEZez>Br>IXMyN27@2xQk&xL1)uBTw;VSl=KTeF`bR zrW2N#^YC%$Bq4x=h9MP*FWFg!%)d-AB#1^kVMeCG*Q7*+RzYE2wEh{m=}SeFKIl^K z@6by(slqa-KhOOksjwKq^pEt`a+vxSBJ4XL8MDV-6SM+()xg?0349++kAwI$C^k$Q86 zLrUZ=jOjo59LOdD`CiCIOtFlMB=PB@uo!YTCr)a8a0O+2X^L9DOQe+NB}n33?;v82 zD@jE2ny|#=C#OWcx9?z!aw+3I^h;4SqP)jvpxF1YiyXR168-OCXG5tYi6tLkwsg5e z5+xtt?M*ux{Qz5%_PYe8iX!@g~&l zb@+h=&yE#epj>6)jyqHb!qNv3pQpoW$R9I`z0oT|=3}1A>F9ln0HsZ1f^Q$Rmde5jy(&8IsTcCxlfJ#r=fuXS`7FPuLv& ztt1r6qB++g{@&L__|d9g(90jLk#P1e=mD;3wu}&>|AvY8a}67zq4mGPGS7VyS#@7T z7}fj+6f}K3J4Gas>;wpE zb#cInT>wWAFxLwX*z1Le1pL+p+WCG028VMu2T$pphya@T7lw9y@BhO42-x}c|H6F) zT=#Y=EQ-*3FmUF>ln&nZVXBlsI%4W$Lm&SKMau_Z6qQk#bR7F8XD#om1Nbp%MCT!1vvP6R8e_gO|C$?JiwQu5qvcy!_SmO zi3BnTnmr#?g?V4 z%vIPjClp6zDx*JCXg3b41`}S!E+?@v8q*ZB@*u09^bi#ztIre!*Uqjc;q`({E39e_ zNie)c;r?6@dUKvH@)2duKzc%8W0fD9P)0p|qIB|lS#bRnKcD+^NO`XZXIYof5%3!d zjB67I@3}Da$IU=CqKHo?1<~=uoP1fDcukiKrgS0!V9fukYvjxAxgL5+k#1+ z?7w&QR|%E~ygHp^QPD3+@XD%&jqsy2QcU74aH=m zpZ5`UXLi63aae&_APXuFKOx~LSxCQ$rzGLl3Ep(ef;T8$d!2 z3sHC>Du_-pKrrvPFV2yASFb&dl#EUM0Qk5V=>0WGvL0n&GVzq17 z2p@7(hUOM|6Nm<)`_QF{V-CEnP=;<3TT8$?D0(e@@>alR8g%?&)XSDSgJBzFyDO~NQo-b8vAj8ji~;cw=HLYJ=a7wix-t8(&Z7O6Iynf z;QikcyHVwMroT`F7C3kNkc2Jz1t2w+$wZWBVwpHyP*YlK`bu?RF~58Ygu_2oKy>=N zuR!y)HGt+%nhp{EH60jocP)Uz*Jhy@vTPPa0pDz3K*4uNrOg#UF38NL3usEGGnFm? zsnwjGtOXs|*`W!vf@dp8RDOEqRsosm{93?x<=hStiPDm`Wac^v%&#W} heightToteMin) && (height < heightToteMax)) - { - return StackerPosition.Tote; - } else if ((height > heightStepMin) && (height < heightStepMax)) { return StackerPosition.Step; } + else if ((height > heightToteMin) && (height < heightToteMax)) + { + return StackerPosition.Tote; + } else { return null; @@ -333,6 +338,11 @@ public StackerPosition setSetpointState (StackerPosition setpoint) return manager.setSetpointState(setpoint); } + public StackerPosition getSetpointState () + { + return manager.getSetpointState(); + } + private void moveToFloor () { Robot.stacker.openSolenoidBottom(); diff --git a/sysProps.xml b/sysProps.xml index c7a1001bf144a1500159fd22f1f6c3a9acbcf48e..391ff63489ca6f3b7e53e69ccbf8cc8ef5b9c3f0 100644 GIT binary patch delta 36 pcmdm|w@+`wK0$tC1_K651~UddAPt0*{W+{BCkV4_<`FVt1put_2rd8s delta 36 pcmdm|w@+`wK0$sX21^E01~Udd1_KbB?9X96IYF3ZGmnrFD*&xv2r>Ww From 09fd0f17f5dffadbb3bd067a55800c62d53b3226 Mon Sep 17 00:00:00 2001 From: frc3316 Date: Tue, 17 Feb 2015 20:14:11 +0200 Subject: [PATCH 29/29] Fixed setpoint getting stuck without stacker moving --- dist/FRCUserProgram.jar | Bin 1780426 -> 1780684 bytes .../frc/team3316/robot/humanIO/Joysticks.java | 7 ++++--- .../frc/team3316/robot/humanIO/SDB.java | 15 +++++++++++++++ .../robot/sequences/PickupSequence.java | 6 +++--- .../robot/stacker/commands/MoveStacker.java | 4 +++- .../team3316/robot/subsystems/Stacker.java | 16 ++++++++++++++-- sysProps.xml | Bin 5950 -> 5950 bytes 7 files changed, 39 insertions(+), 9 deletions(-) diff --git a/dist/FRCUserProgram.jar b/dist/FRCUserProgram.jar index 6d906ac0b80b97b43c75b2aa7ce3dc61d79ae920..92315d8d0b6defa3700670a86352ce109674b47c 100644 GIT binary patch delta 30907 zcmZTw1zeQR(}$zGW8}67DU* zEDfu>F-KAXwtk5}o*ah#Wu#%YM8*LDQ+&BjT$uLDzsJxjMOF+xsN96%uc}_fP~sEA z82U;*6hlolx#?kZA=a2sv#bSRuG?A!COg)$FyXgR0;K+|%@97!rmjgsZNo^?v~v!m zFdyb%1dE?KOyR+_*m)VIX`E$}X(sN(|70g^%*_zi;c(x^L`Us)6VoTp*BcWJsb2u> zqCPTE0>eKDx{A@02?@r~d!ZLGl;=_ng5+47sZQ*E*jKT%=qUSoh0AIfQFv4VhO%9y zA%RUv+&qKfQh zVlch+XLGhOdX{<5h+#d>GEHJQkRHj9oHXAu2eiRmFTL4vG5Ub0c)X01E8~n60z{M+ zJ|1`cP%|0rguCYtaNCd3q{#2!9hk=M9*-eI5E$gmP34Ad4{t>L+WpKDb;A=f?XIIB zd${MIB6rbuwlDsgC7BO-NT~eHw`KZ-{N$gjS3Taeny;}v<+1$g$Md6L--UKJrhu9K zOJ5W^I+$61-KI40)ODgcd1UD6@Vwx3{5)Fa+3A*FPYhhttlk7Lek`w7BhV+QXb|PD z$dmeXyT0s~foItZSBZ;@kDY8*pPk%rD-geBJdKhk+gY zBIZI#%sEE%ac4bxCoD!^d>K+?F_#bu-MUyrF^AT4Jw`v}{z10qFnY1;shC=Bc`enV z2uW{Hwo-=Re1A&EdrHQ?M|_v_Wu(SsnL$jIFAj_#Ak z8$-WtZ=ZNzC`;R%RF*oGV~Jdssbi$5S65?5I4lZ}_Le=57e-)mqvk}D{u`E$r)+(; zzA+E|Kwr5s!`|Z$^-HL&uO^&j3LYX|kQKPd0M+Pt9Baxc)A`9TY|&#GFSt4<>mnQb zUeV96IYd^j;8DI)gib2s9$x%%c0eh^iXlVd>iBeN4#n_dj>jn*zjYfc-WogGd0Md# zTospi9$fD>{<|(rb=LdDLu?3f2ys4A;@})lQ+MD>^KT+f%P%8I`&mJPzDQ?D|Es;u zP?6l^S>>?=3jqQW6Z^Xio|@By8f841G}_N(viZzQr32i@npbs~5Rk=fp7 z3#^Ocs7`;{E4z$)LqkG~ypta76j!ce)N7$U!oNw)YBWdvF^7_rnRXXJNfs&@18EKQ z58D5XkK*Q9=I-Iu)eOxbOD2&QbD@#q%$Yyb!!6Sid4K5jJfCLgcC6y_j^|(H@Y@6n z^Y%Ox&_MK=rm|D z$9wVNvcoGWWO0_4cSx@Zn{E(uX{kuP@rcCzM7t2aoQvNs%mnmAh6rtVub*&z_ido3 z>4ndu1uhBJ-IH`)C@a3ADRP$n2@yokjNM*#^ZvedhFzCwn)X~&7DA_ddpXZCyO1=r;-dxxHL>I?;-}5i7ce~ zpf>s7lEg(y-KwWyf%52d>yJ%H$@`N9oO5H$jLF%xA4>=KoAJxpY6u&P@0C(|HMuk* z8IwacRbJZ5ET#zFYBHj=iPaSKJq`Z=(w;lC1b{yT6yI zpL-dk@LW%@C$NE5Dc86u%Sgy)iS1b`^38>8C+~W{^)1HhdY|vLAo+Cf%RI_O^3UXc zjdqOJ+LS%0duOFD+hS?A(k6bE)pn?Gl}u1{WnEeHp`pN!_5Rg~Wy6sAmOYMJwTnYv z^)9hA8w`hWhBJA@eu))F*EN4VYh!2|rc~0n7C|AcKkf7Vg}P<8qq69{3dzhUR{;af zvpBS|XJCuw8_2>XHCJWV^A6X1Bnij7rlP5zq;I)9A8V0J;Rmh-?uent+4LGV)2+)| zvNS&1COi!RYxi$iY{m20(kpNlIjpXOf1To=gvrvvq1BC%OMlfttJO_ zi%zvP`MKY=>KhP?dKP|CZqDz;6CcN-c+=$a|Jun#vYEU2M(56RM zke#@9PV`6lW)!-7Z}dqh8rt!^V>}Z%9i63n@!&$4@jKO$@D0*fb{2E}JX~q#UG+6_&G%&^Zs;|3OK7MSgflO) z8Mab*U2qTgckf>v8k#p87CjkoJF707x$$kvo-L~uX}tu=NXmD@ShNhE1Try8M|`-E zejY_ylju%Wcq8R|YCkS>uZqEwF!~E9&Rguq?C4dUDQPX&tglvf=tYyPzSk7eiv9HD z%DpcW`9!u7twsgUmkVBoE<6_`ySR03hjGg#7mlxNP-Ye>Y0<>{fOhVUuvC|*?U!KdR6th`N>{uy&jHXyTj__F?G!> zkhP0;JJzGS*Tp8Cd1OxweZiPj@ujj9bMZE{(V|54y!LFb!2#+4dR}+@kU)1=IBDS` z>p;GImxg@b@;e#3XlY;W=e5Mo>+!{Et~U3I*t_fcU(4+a{&+dVp;tD9LQaP^>Asqn}NpXX%p5+so$J$=)q-S)!iQ&ef;GIcQx$PcU7M6P#qHe#LEuo-_2>&vzs28ygTu@^uUew(THL?DAmbm zoQSPm%B*d5ud7oP`Tex0D0ff2V2?}5<>Rde*M}4Cli$b)lA^2`S4Z9mRTX*Xm$#i7 zAU?AHv^jr;=&bUSJx$+FH8*vcH%vL$d)`Uq?c7?@<4BqpL>liM-n{7%#%G=1v!~4Z zeu049@zXpnm1CyFi#4=#UE?WQ6nAE>SjYGHjkdPX6wUooUwYS}aH z$4tY|!!PfDDCl-?v^-JWj4Caal`iRLoslsA(7h;9nn{yqOl^>I>k}E1oS%p5)4OLb z1zckLYW8ZwhFT9<$I^p$p#6R9){jQA8RGR726|_9BvyL#Y@Tk`+ zi3+unXUfSgCXsUTl^>)Mc~``dt==)nVB^mWL1oGQniu%yto(0JJ+|pE3b-&#lqEg< ze(78XZc!f=XD!|4oGMS)QU8_#AEesB1`%-rx;#ItT1~u4nFZ0 zl$JZ##;wRGuCma7$SZQ^eyoGG?CdQAZG1h;mll;23{}owY%hFIuwZy)vdI%`%FY`~ z8#x)#EGKKceDOHb2>WxzaK3xj?YRRZyq@Y@7&dE3GcNVCnRHM-?T5CBxNkNa`$(tc z5smQ15`*8)aOrgI*Y4@6rm?ppb+WvnG;BWlkMFl=mYf}x97ERq+NL_KagKN5{5 z%^qvkYqrX`=JuwzvPNtbU2o0(J?R1^NkPlEr{n&orzhi%r6(o+qPg-|HR(Mgqc&tO z^f5KZ&70_E`Z9B-!gNh+d%Hku)hGRXqSv)p&VNOxl;1I-3~8AV6Vg!0HmCZ+Qb}fL zF&(>YUXL6Oxnr2*{M8o^ zs=cWty4DQ*h#c;U4L8jaW2(zkT4r8tm&E2Hd`CJrNhbN8)Wl-E@gd_LV;SuOd7|I>K67%*4U>JNcocWMX=}`9O5egM<4OH*H@4kxCsX%_ zh5o|*_dt<3sONSf!NHlL$H9^K{dR*yQz^LDk*A6ja2*qQR!cHKN{omri1CjhMEJ_v zC8W*iNu9mO_k4)Zv+*UPL6vpYi%QGsN&=q(27N{z(ekPng-z48o6e19Rqfl~JAb|% zT7G?&Q*ZCP+he)yA8+>`??t}dsE{5o#%Zn{~O8vRm)OTzMdTaQzBDLxg#kxkgnPLxe$>Ai;=0s8v@G z>0{A%N>X`{go~z~eb8smQ^8l48}vbWyd-f@v`k2#rn_r?+OV}5l(^UA@ zGE(&3<;|EJn*K(7(eSxh+)(_C?93>NuEpFZ(5id2Wz)8mQSXrsSDjgqt$poDC(}vK zEr@KAH8rRa~d>n24>Gtk@tJ98_ro0y($Qbri-AZ8+n-SndS1|Cu z+FK_#Ka-|^d_ClnmM2!s%!V`bJbK| zi^0A>n(bMWzJTW|T0!Hyy!YSwH^Yajs6TFazq8dlQl8Zzc^HHe13M7?^3h+KoYeXW7oS} zwpd$1rBZRZ7=6+*_qbC+O$++Sx7M|2Toy~;Zg-NRK>Yjh7vHHg{5tmT$w-dl`uDt) z-COa{E*?n+-q+e|-poeD+OHO`n^;`5{-&v4y{KrfCoWbNXq3QC<(5tkJv}Ih=U5n^ zWjyQ%6BGFuA20g4a*;pOvfoGOa{Mc|9IIXFwt~e|hdHWNyNs7P-$6o`ubnYqoQK-gG~vI$P*xjM}{evY(ZU=MP$A_P#5& zD!TD3F7mO}^01d}RWlSWaWeesRLgGRyeG(WYv|4a6ccwFN#zw6)7V2IdphKaf3C@R zJj*E^Lpp_m#kU8^F)|o<*^pX++|*@&y{1na_vk zeX6yID(!-2NZq=_cgVk&_1fB9yZ}WT)igeHO%2+vQ%1h*^xg?E3D2V|WoLqC=9HO7adOu0v-wmc#pq4l zB^-R=LvAYL^3D4V?o*48v&`qplCy6oI;XUtK2*#lPepZ#B`x?mP3o_Uw7Ul})f8M) z^{%B2ATh5iU@^QAsiBr5M3MH9=Vq`LI+fG6#82j7^B`TO+eHH?sMes6td8j#TZ`PX ztcmL@RDAD00-NMDj(hnKh=_)3P%ib4)n#JU9$l97E>jtBx zw}PVzO24-g64)3^x{!^-%pf*6CP0~7i|6QrENzX6*z0L@ zYjiMOcxNkPm+(lVXyJOjI?t5Z@K~e(T4``0;K7OWpJpsVUdW2v`Bd}vR6W%Yr&r>r z-9oBLYiRlOD${13UL946Wog#Ra--$WGw%3P`pq2#-$s^X%nNk-3<+0;aLMnykhS>K zwIW|2?ie77j<@8UHUXFvyBs_<&GtDI|Y0-J^B8I(nMEl|cP|vi7IjLJZ^t|vBTi~A zXg(zVcx9zT@?*+CTk1%Kz+!y{qECV~0F9s8c}+r+g0bVngT;q!i9+)B1ozr6%9tuv z#FYBgS{04jvFLK@H|>-=5$Uk$2vV_HTEvfe<-83#D;bOvk}_v>v#;9m{y=cO`-l1Z z%q?!)!?s=dFa|?o*P(T!mwk`}rpx|v1JSv+a}a$p#>ZY>r6Zi+{zQ21S9B4;P1 zVf&#et8l4g<$W$a^fF!5Xqk0DM*k4A?M>fs>nnExu5?KE@ddTut}ie-*S<4WZ5%G?)KnV$s130-M#iPH&)Trs~>DB#5Q^hMf-G31IRPlX}Lnf zP?mR|T}_DmXp}FqtJi3p`K`F0e=wqMmR~rcZk)gI3TwYm@?PuVBgOptU!J1!C%>Pq zI;NsG_WV8`CHIN#OeuZ7(H`e-zLf0RXx=1gDnH%PNc($)F ztBky3Y>QIbQJGC(+Qo6~?m0YAiLrk2-ZH1tCzSTVyVE&*ixig|A3uHgFg$GOLO*xU z4(Ik)XPJ~FH=gvJ@%TV@M%S9e*HkGzjn}k);r;tGHp-HqBZ!Yvzuggqxy%UY)qpQE z8hi0EmlLghq?l`!fhUy&*h>mYXmb|a*i=7eupC`k3z20OZAuNAAtw#x8VieAH z7+pl*;OG*h)j0E}iM^q$cbUn?+=u*_GlP4WzS+WDm#8ni!dO79U@m6Bosc#SY=Ln~ zn+?Ln!8rg{RN%)%XnP*Xj?Oi6Fkn%qSCKnS*Q#T#R#?SBwRjcPRbXRVY$j0f?NYac(rP`uarJ1SI-&?<#6Sn#f;>*f`gWLw{BnGYKvD9M%{F2US+2=Ui;pYV0vpVN;r*n_j|%M*FhZ} z=b9Z;XnCK5I0G-&b3fJO&GZ&cTP6uZ!JC(HiqGFYu5*}5w#oLnb3#YO>$3!VLf-dE z>F&!juY*!Ov>!xM#F$IHnYpxQWHTXWbavgY`ql}zMJ*yIY#KQ*+j0L^%KSw`KfK`b z8$md83!k`d4i9C`j*K+b%Vab(oMfdQo%5vb(E;(Oa9(T-U0s zqAq6tSD2H=-s!6fb$rGo6H?@4_a>xV_FhV_w9NG=c4X*X*6jU7c5st-IU?ca1Z!@g z^0b|oU}p-Fy-`fGYm87VLNG< zS{QSaOjFxqfmQ7Hm@%S|&nyTExBy1`CjB_@aBz6j^7i%67IwyT>hwRai=8{oC?G&A zAhcg+pLr*0R_jEBV1H~^@54>0^sc6aOI?F%V;u8z;;61(qBExsP5Y%MN~*?e`uJ2l zz6>e6z37*H{;e7sS0dq(q8YPKr#v5Ol&eo(B+Sgk?6T3?h1;1fI@9j&*D{k7h74+t z^=;xa(%HDguAt}alP-}@AYTohF6aW%yIxuD1EJN^v1xm%AY^d* zSd!f=lfv~l+c92UA5Fn{!*9y+f!dNzHsuT-h?@3pmS5EWR`4O=M6&(Mpbs!bFZ z3Y4PV@Txqe{m~>4g}r)NG{b#V^Ho_quba%Cx;LVo*TP?Qwlw&jOzr3E8Ar>cI;U)3 zdzrxPoUyo;&NS5%5q0qi_S+y zS{|i1iEBFAQ%3j>XSe&Q)%QoMOt0|GP-ILGOKl4Lc+YkZr$3{hOeiG-@6urOzTTix z&tdF=9gn~!S|^UioO!rd{SC<{bF-_KHaamc$|6p4M}KiWh8Wg9wQAj`@A-pmy^-$o z)Tc(RFFLj^{BG5hlW8(zF_K?j(tYERG`0@-VjbXJ?&HO)U{iheI9K95RqJne(+HPI zA`3``9k=>SHu=PUmc|8t8x61Jkt+ z7VA0;25(0;H%Dc@;tPhGrzZcz`LhBs*URMJvoK4p^e_WMReq*p=)^C~I(xW@i^~o# zIEVrtR|n9CmiV~R@LvBgo(LDSN*@xC;-^98tJeLdl8uvL^VY%8Dh| z5bL?wGi%qB_LKJ2wNKs@iH+-Jw$`8QWuEC}Hb>dU@rl@FV9Oqq;G)}&?W7n_BGxZbe^u+k9#**RQ zB=9#q@vJ4Y1Z6aB%4&I6+|4#@s&PPeFk~q}SXimjY;|pIJwsI5Rk3bUVCr5aZ<)ad z zyNpbB3XU1cl&U@fBr>~mZm-5JgxLuD56@T=P%67};V%vzBbQ_#PQRyl_d~@tmx*zr zX$3#&0@nllFUs266rwUEQq%1k=FzfC6KRNB_K#hE>4xoB-$zfC=UqSb;Qn}$elDX` z-RT#l0j+6-)#wv)r#`l24-6GApXI+!&sCXbHo*2EpkM!$ZG%Gbdwx&3bQucWg4Czh zatW2G$Ae!;G|nO-Cp02uO&ZG#ude)5=m`;Zv8`+Ix@Ro$Kz^q0xmAoGWB6o_urZ_T zBYLXE3!*{VO=R)!(M$A~xLk#-jEw3-i@9zMYD4{bCCISobLRvf;9lr^GRXV>aS1Aq zRej(-v#hxg6rs6SkiqVGmr#|Rx%X?RJ5DNbGUF{DPS3}^aeka@GMnE$9p0v9U0pq3 ze4KQ8a;PYT@+YO_jh0L7y;g;$QUuXAh@0b%y`tGUK7JBk8^;r^dBrMv^R+1<+! zJrFrLY!SV#>=qGS+u=RChD@#9ri^sZ6q4H|b{=7n?2%XN7I$~2$0<&@E5obUZXg>${?yfKu1do%U;7>X?bq(?sbk|U;SE=!)#%vE z&94+*r9DgYgVxy=eY^7dy}|3lZauOS2af~gw?q|YJBA*ey)3;j)$$_fJ5%nAt?aS= zRW8d`?gTckY@Lg;Qs;~V+rOUicxZ9U@*VF7PF{S^vRQtCy%|&EKzawyQnha8@Cw3j z0;!kuCXCghi2T!k;*4;`nJ$VsN9EPfnWPq$d8WL{nh0g_n(ap`L`3Z!kh|U;T41s7 z#|vM&e1cJJ;@%gs{#{`e*ADf8?XzEr+8xkicAuH6iCxSZMwJ?980M#v<4Wk zcApEN-Hs;*mT41@KNuCRJ5{0~#Dok|s<=$x;&StFt5o9yXE6Ej=dO-g*(itF zmdw%qeiOsdI=|1;Xr1cU&}v;tT^=`H^>ivhRbYq3k~wik%XNn2QECSkhkcw6Wn;_^ zgOy>v$5K0%hHZkS`zyzn+r3wn1YdXR62B9BIZx-?S+=yaGTC>=gsW6==ZtA*M}NSO z$q5gpPZKAUp|oILc1Of$2S2zNR&0qRbKAdeS9hD8HcIMz^zJJLH8fjnYSjoGzrE)QFzrxNK(QFcm_c|(B>ML^^I+1|)~ZPvY?JS*sVWNm`+L1YaUa( z-*;&;_Qa`srMg#0igaI4NWU(+akZ3dVEw~~Orqc_1L><@I??ll39>0}76~@72K;pm zM1(A___?YwPrjTW7p?4-ZMgj{Wj@pTzZVzuF$m$Fm#l+IehIfC)=Za-7&XilOao*9m^eoZz)WpnWbClUA{N`f&9 zPRW+84$CMN)YB#EC+Ec8W@%uqYPs{p@q_hZL2b5{<5uy)Lb(G

7~p3m2PJ_>h{d}(1lq>w=><>Hw{IOeYP4lIb~TyZfkj3cERtpUCL~Hv1tA`$AMa} zxSxJg7G@P(^86cv3%9yz#?Oy5hUh=k*S;Q!=MakMBNWw_{4OhNG;n2^epGnm0)a>E zh5QA1&YHy`(|GQ8R_4?bgz1#SEp)4twRRD>#i)qs3eFon@y=+A$(JulMe^nG-zC%M zzs>2IHZ59?vZZlOLn5UQIJj@<;B6CNT`cdZ7V8iN|jlOMOUyZaF_lA?9 zWFZEj|*)dgyKjTwkLio_G z=n{Y^YxMphR1! zcK5y4+|C^0Ha9q(SrmDFb<3C@=pArSo@~yMRm#d)TsF!KkyJ>;L%cT<+wen~Q%>4& zEte3#v*Z*ImhbE;XHAx8Fs4MJ5~$+yg$t8U+|HVCb6{N-`++d^@;)7^b2U1DHM zd52_b@`5YvdDevE=Siv!rbkU5g?@=GWMub)lY z3!@NI&Y3Hj7Sgh0=*w|aeljI_XLzq0EZp|H`M{R_-Z%3z_k!hVOHmXdHSvc6&rEhV z4KwFR9ydM{mKIe!TlAoyR)~otl12WzmqRkAx%E4m%6CPTq7IkRYd*VgH!UvtPHPREpY!cH#b+xPyJ?l0RcLgSuanJ+YKNU-HEKSK@OGd}hpoH);U ziEfXw$J${wQYk=97H_~*g8XS_DMis}X8d(iUxSGorW)fn-wCkkWQz{7_A4~W_%PQe zpRSIH6DtWPoV})e^KKNY08PoKjBs%we-3YdHLH2t`vX_$V{UliqLWkVlMC;N@XVMB zta6G`>xmXpe6@O;vp!?;_^OqZ2XoMko$KrGvOb9SJ>r%>f8m?P5^dzodG<1|{F7Jn z(ynZsQWtNU{=`C1vl1>fY$AVM!M>2S$I{4&H&6rBeMpm&f6;)H`vhxf{K15mycubk zILmW{T#iSq+J|_$;66e0(BjBm?-~ETIJcgF&nvu(;;r+w z)VQc{7Xtd$F7^oq?Catamvu6%R89HY{}ANMS*w=+6nepbEBb~M1u+AS$rN$B?rp}# zC9(bVu<}i{>{pS}j5TK;4l0LPzihOga&c&Wk4l!0_{Qm{Sj04yi{_{D7PZtRKK?4u zgY!`4gGivqaURno1s6)jghw_yf#6N#lnc8U-OA}|tBGjQZrZGqQNOwv0&^%wBafdT z%E+&{Qv(&-lizxbqflm&en;4`K$FMcQb@xfZm%+OX;gu`*-1w6^Nulb+gE>@m>uZL8df!&xP7b<$k4$x?X2!hllKo44xxE-@Qb#J&wlc;E7uAcgb6Za zYYAHWtX5rEXbai!3h};cd3dkkH9Ywd3SDb_OVWLpAvT98b!Tx-b-hp=*JIP?NzAL~ z3Mx>WO{9$L%7c?+mFTx!u50b`PVa}hEGUatMrUd6Kh;_fd|JTzvmtonmBJToO`A)I z^V5E{2@gFikTlWOp9)RNz5KNWn|~xSQp>ysG_Q{XjQ=em75kMVdrRlD+!% zjs17wL}II*VXK`>?k~IQWL&9K=b6!?FXTM}`#Az-*{!1;ZdUwa>tXyse4JLi%q?>Q zZ-aLHes^vteH8j}9ZWTPkFx419I>EGf0O<}>@+Zi%Fb#Zy^n~f` z6Ql!7m7XHqU|RSTtB?N-I0d}hGo&RW1gGgLfFvfc!@WI$ z)j2kawRvX}8wuqLAjT=AJLV(T-`_mP`3S{LA+3+WZxR3d^*`_pK+K=wX#1Kp z$udDma2m;t(fsFo9e>mSEsh>*!f0kpBN^a`?oT6G5$H}BOXKKdgQ#ba@b6GCVIxTU z(xQ8Xgm4k`c<>Klu&*-5-(*YG08>9flmExG5v(o%rGP65sCxzp{{RJg4Tg`f=syyq z{ph2IlxML{^k;$4>FFOKE8GE234(kC;+#VYikKMu>w6_pu3QCt&~=L(d>Q{A-=>%z zTA0C)oxE(K0=^}=N`ZqT^N-fzB*rdOJ%>cX&YsR8S#bj(^*2Zf;s5pZ->nG_j`lxR z+Tacr7*~Jce+5L1v#Fl>Ce8VcJhb@+JJj!Qz_8X~Oaroei^aU&0&IFA&2&K@dj1}T z$@^Ovt6#zNm7Pa&!BN611R=DZRLSp$c_hbCR$Vs$#+4?q zMMU}UU?Kkn;GrBNhH4g&T$r&PbfyY&g9{&Dd>kCbe~c?`{WgSx#1^q*QC7F;Q4{9`%`)-=T^`L2V4Q zSVCIE>3X&VMzeDGmjMch|2>ismZ`l5vdcgJ$e`r+zt>!GmalIsFkA)V{WlbP97uf` zDV4#1O9ScsK$2r3=O&)G1P`wRsO$U_hZq7@x4@*YdJ9x2KFo7LDJ;08|2uQr%OIM} zzZ4*a6(kGBL8ys-7!4TY8gO9vkAp!XtU>Bku>HIy!lll9ft|(C6<|$=^hhd&$(ZVU zOThrJ0X#(E;K==BXbN&(MZzCgLlwXjBA?|bP&Uj!G2Q?Bboze>`UH|(Lt0{j{qF;k z|MhWK@W?1B{K+;EG_?j!m?&w8Y#phDS0#-Lr8*;cpmXa;RXl{ue;hr;DvwJEeOgBf zA>3r3V;_(bWH-RfyPXXdzv%A;MQtG2pbtzaN<@_m6#D_Gh?tUrOm~sY(Ci1$g+dl) z_#m+jz!=LyyZ9)6C>myN{bsgnafzTA7@7Tz+#SFrgA_IaB6J+?AOP*`;1WV9)l7q_o6k#=IF>O8!{vc1k{Tl32fg?%{f76Ey0|hB?g3H& zYTXB&-(JQFj$OuOf=(QOaEPuSA>>g00Z3l_jlU48uSgjLPdXOy{fg8@>}6n?*{{G} z283nwzaec90=Kcu;5VcO0-b|pI`81pLaK)#GMn!pGLjN33~GxBO85mTbOeSIYyW}; z4?#++>y8is=+PmF)TZ$WVS@yJAoURp%|{3;)cgain&y@xgaTs!3D)k7&Le~f8tDMZ zz5f#!6YImmn2IL-h15h8_a7k)aAb0bGf$2X0mzU9MV-NoLLoEQzcNiclq{lp_Xrk&?$U!AdxHlYjD9?V>7nEJC>2EX z{t-eBjeNmng%p2+a9-d8?Sn&D=8mBF3De_HG66~s!TSr#{3JlhBg}B10vfPuL=m8f zpxeK2=^;@9;47XG^qxTcB{L!d3NwT#O@uAMzpyf5hv;8~9O@?mj_^tU7giufNh0{k zu`t+Jh@kUi2vH~;pM@Mc@d-%)y(UH>5nn0)Rp5nmNKg`pk2L?n^pFt^f)MH?0ZIHx z_m>Ps3I?`E{}-Y}k6?fmsi87bFfcmCBN;Jd&j4iWpHP?x@F6BLpuo?BQNV0>XUI_C zxu4}9fB+hV(KN3A&?!y?EtEqITv(6;3!i!ah{&NLa+C}rh5rwrjnELp{2MZ%L@`0v zC_qk@ME*j)z=);95poi7SNe!ygkDjCWDFn2A`(<6eT1~a5rcw~w5tNPXEUEV5~cV1Z&q{^YTX7MQRwfePqQq7W$^N(!-S3NvDmFC9u6fnxzP z9$;s4rU&IGK@Y~HYYit7f0tp^9-nCP?R;Oky%@ygxRS3KvzVJJ#5w+vE={-umbNF7=bTI zN0^a<#$g7HVI(1OCJ^}KZ-&DWK@8c!D@OL%~E6U{r8-RTdWXcBuOu2)gg5K~0gO>UK7}UFqQOM**5ktmYphrW|f51*5 zNJa}6NS$TbA5!U%EU@c8;C?629p(Z4X!~IlJOKBBbrrXZ1bd$V7@!m{FcI?%EA!z6NhcV?GRmW1 zQ+dt{x_*3tMFd}f;6r(VV_A>^gv1;Sn`v@B7`wqOjz>(e-06vc$Vr3%& zz?U5k)Flc&h)Vf|V1iTyL8Pn%M+ga&BnXm0L;e?HOom4f9m0xtY5s!WP~(w8HTobD zcOl^8G{axAQX!CiE#zMat}rOHWsbiP2VtW!6cd*P8o$X9XBD3qQHM+hPGBM9_o&jiUMk_27vg&xTmunSHu;-3J8Be4o+01PEw1^t@gexA`s z{Rp5vNsy@P*Pv8s6g%`d1}KWk0!1$=pg0zXg-PPTq_s-}_z4WJq+(%?R1glOG{|69 z1{N7j2RUt)0*b-XK(Q_xhOH14xsaqBFi#`{O6FS;%y2?aqa1j)QlEuo)`*X9VR{S_d5gygb;<$9m)^sXvp_XVcr;LTIv9|E zJaB{i;RpslWm*R^%xn;D{gd`@TTp>Kc+jl)2vc^5UjdX~`WGxS^ckcWyf|TZ(NYCq zRsS1SG_L@buKzDAqofF`{x}{Kpa^QVl?bNn(6S;Z5=(L{lSqb713i<0Crb%fS)zhr zRtQCf&jck#!IK5U=5&y{GT7bXY4O4H_d5V9FyjBcYDAe}1rx*&3Z}=PdSx(49_-j& zd2GN3d&i$#3#b5#pE$8HVNQHzI9tDWp*UD}Qvfp60zptq;S)hm`GLzf#=zwUETa=W zl955;s$fHP75@uKRs|=*wA2y8ggw_N)IirA@G|_{EDiLv0!4>ikLO_7j22era}tEw zqy|nlS-m5K1>!gXrjzd!7O^+Pr^2S}w(&nnNHW1HJU#*H=cfghL8+roAd11OFzkBT z9;7u{9TxK@Gw%@*)-{(gYQ8 zHv-E{Ujpw26~}+?X{1;F3GC+;tkPpmFe?fPScX9h6t;Xi%$z|KWnsZN2%ij^(*gm$ z1P3u3AaxEt8+86Un4pw1pyaK!LCHtwV`Z&*z-f*)&~5>Tuoftg_uAknI#~u65epPq z3Pzjn3Z~9k2gH5i9v05h0qNO&fMvk{c0>c=>w<(^G#nw!ke4nnD&CAmYIH$Km$$(T z3Yu-j2R8?Oz^L>|U{taj3sdWXGwj?+V5jxTUr75&P$5pwj}TSFg9)fs4w#RH zeg!kmh}SbP<%g8?K~7NfFvAVq)(11kx`btZ>4QZRv5sZj4Zw+X7aX{-+G7I{9mhv3 z!)^!+41dNlk%qvz>31xX^bMa9Iy41w?;C=+Nq=GCGGOAqFD=GttAaBjP6$lxl>sMLb}Ec@%WQ6wD8~F?fMJ%kdYI%T7QK zali{G$r$ve=l)A}ii-ej`oYU$S9A0vfEj3RtEj_LpqQ z1Y~SS@(58zn8`w^=Aaa^P2qJZ4>PRLjwu-PzA}~(RR$rPHUlA~p1>jlYQV#*1{4iM zqD4UU*R$lI7FOY#8OZo?J(v-I&X|KapEiUUM?|qv$Y?<$5;2 z-KpdwIRg}F2MiR!@U2uV{5G9{2zqM+%Kd)E5kikW%4|*pMcms*Fc@Jr0U4Bk8U%;V z!@^6aQF@3o;24J|;-oFu$|B3KOid{P8`NP7bo=ieA(RlU9jF>>aJs`CfDR>;RSSj& zA`?QCHv9#T+JRaVYCb}UArX5}FeBhG;CELdD9#?GjWF%{3)!&;i?y})2*HPR9Dp6L zn?yUHED-e*Fg*rsj)RJbcn`8c;|K<6`Wl8&kkdy{Nd}H6WyI#pUkKF_7`DU=wh)96 zua^FmF~Jifgy3I4f@vV%wLfJe|M8#s64^V_V#7}8+WtQZa|c)jQ74odUOz5j#sZ-T zR`H$_3WcXf1S70a6d@rqoL*{(+!??TWLS8VnveuCaz@GE?NS~g6i~G@N)9iZ<_H02 zp$kd~FAjx8I+286pNESh%>@{fW;=o@p=lSCJYEzZjG!QKSClH=fDo2B6eMJT4+bGT zW^pWXN{o;eyI6?N0y~n@FpPv$&!QCZ?i|N5BeI0Qp9^bYowJHqI7@+$8Y-6r2b8}j z*Z_&$P)IxmRjf?K4TSJQoe;u}1Th%v5fVY!ZYW(mO`ZQBDu~=2j2fl?AH)qsxr5;5 zPW=ZFLCGG#g?%nqjXUnZy^+QL6DoS3B=K_2{12{zx9G#lv!6H6DvtRNCxIS#qxA5CV}C>UZh$FJF#!gZe1K|N{BQhe93dSR|BygP z4enC^yvV=3NeHDT5z0VfH^DSudgA+n6%djP9rH!`;NjiE$XTIEUz84BLHciw>KsZ7 z&m`+VjtEMEz=UCHCi@(4y>SQQ8oZF+0j~2UKu8~9+~e+V{7yco4MjgN(9I$Mm4O^a z`=O5GEtg?9K4>16eZKcwCUlRG9Dc8*hUg#sGXmloj0O@?en3bMC7uVJ&NmT4V+2I( zkcvNeM_V|LQo_5__8+8zx7qn0M*@j=g2=(cGC9=g58lYSd!c!Mlmo)%2~2q)*8s4E zxDCO~F(`i!Bsd`uguy#P`1i4a9K|ZI1%fe@PyV)lArPgGXZ-p%7yAl0fF?51 zP{2qqpRr>}Vk}rl&=|!=j3q^*i6~aos4=l?bgUS=U@zE%L}ILnnixA^EZD_@VC6ge z=H+@{{_%Ov&d$!x&i1{yTR7a}9=Ld-X|YqH?GUt1!DA=#e~gjg$PoBtYN?Yt_!O>k z)S`Ye3bMa&^4}$+pvL7+l>8bk_bL>AiMb%{O~x9rM9{3^7#Xvly1P-d(D~5e-EhVy zLlHCZ`kS-|ZaNDs9g1nY437WDQzN)(7=~$oUuI5* z>MBvZkItPeDRN}>*U&xvbe?ZEO~X@Q$ZkcGzAXitrNvcL#=@(DHeot#^EC-q1u9YE zaAfHgDVc6!c`f-{jSAkVuG=@q${K0*ruaU@9uF7ejbH&cjE*GgFe>TsB9FJ zE1xjap%eU%h__L1WEDfYOFD$oMx)H>pGlA;PJJPNgDH5RE`(}L`S-Yj#vsFufofWH zxqrdgK`Q7e-!UCGT4$yBR7AgLiiY`g7)pgBa7-hmy~e0%&dT|ZcX6%hdlncw7Mf;H zl0czD6A>Pc4f3P0Q1aUprX$BeMwvld#$j|!9fvhw&TI)fi}CZA+&vc=anfj`7UPkz z|3XR{kBNL=n*0r>Gvm>8pDbtDY0D5AjYmSZ_4kl1S;h2Qt8^an$RkP&&R}M3I@;FR zF)PtyDZFDdC*9iwuQ#3m;Uzm&#z-?Jpq#OLrPX#Sn1F%4B#T=!b|RMQ`*Rq~oro3C zwSx>EOvJhLA174cNyZa8liYGRyb3V<`~W94xvXKL z2co6kG_K!dRN()vx(fJm3tznH(l~jyT&1j3I2ngr4IXOfh=UyYHtO*s6n84)G*rip zrj_c9Jd$jcX|-Q!((e9f?;u{6YnXhY*HLUa)P3_4D!sZQdCr9YiYH>1hcs`>m2^j) zE3Kp8DRAQf(|_rI4de3?#Y?a4(N=Gb_{Aw$D(>>rFvY%lGarT2x4YzfOJS*AcD+9b zPm5p|fd(NgFaR`&_E9X=sGiItp0RoN3z(TrmDV9erbEOOd^cA7B=&I;Lvk=$|WTwx9h6UnlW0IE9&E1u*L4Au_U`%(NHbjf{EW@{?b*T=w@ zs61}e#=E%4_&p26j@MTvkA#2cqKpZ8?G|#$M3y=^LGL({ixL4-m}&cy-iuq&cP`4S zG=u3^GZ2VPrt96Q%|jI0U#1iig^Drz&EN9StnO@<+ zOIht=t#u6x1QEh5X&r-k8897J0yYZRji`ecE9G(oW^Lrg>Aw0(9vyM>Mp4AqJ_pay3lHdUjvOE^+EY z=vaM{lTyzkbYm9bQszM(oOO92!n5xg*R%$r%>|VSkSFj_qItf`c+s;(D8A1>D&tPS zT+v%7aWMoBUVlT+yN<%jYr`3L?zlLr;O-kCvfo8NactF;C9t%0F{h1rfCwt=i_G6j zI=MvBc1nMOQDxr}lyts~8FLv*v7~_+`jVN97tq*4GQR(#!7C85&xOH*Hm0GA9l|NA zlkp+TQpk+Qd8=eH-3>N+k%0p181cX3JMBgh;lXK%MuR8C<^0m8!VhwXf{+P z+b_`MQ<<4oo(3!5=?wV=g3J9Rt`g|3HFH zg7BP9nsmG^>XjFVI$!Ky&d@D1w z4ySXwb}+b?iNGzF$=~iF&rL8ceYXLRyVip-W;vPl7-_a=Gcav{gZ*+Cv_D{Q?h-Hl z?oyGwgDl{F&=A0TygM6U=7=LqhiybNJUh-H<~S^zvJnM#KPj0ibZ#SjIp@3toyDjt z^0x;4T4=xs{5ER5b`w;6cZ=yeo8Y3rM-l{4qs^$=*e4PwG=DRia8Mb8qRoi=zh5v| zx&>ont1Ymh0v_pXLvuIVf)OjW9L?-lV&-f?2`%v&M@<|5J&xuaQ&r$rq$T44j!a88 z81Xg*7cewvD>fu&%uHu&#f;!tnSp*AI?p5@32-UqZ8XWZ95$MW{Nizdq!Y!CAo;7% zoj{|F`%BGGqqe_8Qi&L!k0^;B@;p^negT4 zcO>{!#MWgpY6rFnwHh+$+rVg%2OYd9y3^RD+=5ssq|mt?i1qCE7)0;1w-j+7G8o&! zXqV$WCg`20(TO%pKi-K9@$DJ3-i2j@NRYrzYj+`>26thg-wjK0yD{jt8%Xf61Wn7e+HpmA8wN@DxLI8Nl?kuZ>=mw+9Z$AH+}H~ht41;%xDQsWn5Y6w9{UhuBd0MF`m5c8{@RD3{`Jo)^PX^D zqyi86@mH8#xJ<)@EJMQ%s^)aEE(_%y#qL7-bO+J_O+H|Hbtu@3uz z<0jhj8w4kBH2TZ?GrTI<#!SntMsFU9C+|nr?bvWg!L0ol9&7JqFfbdT9h{BbNB{jQ z(?m4SQGtQR955OvZY4~(oeez?|KPOH-!S4lJI3If-_W=ApOPR^bo*QWR;8E&7+mjM zl0c!*OQ<8Z|JdCZxCBuf+@wgm#uT6en8`TOD&(Lj-)l1P1E}>?qmP^bqr|QvW@hG~ zywckY?&RQ{b`-8crR=7AXyYEgLss{MnU}xYE#$Khi=AUnT}s|xstPm}4PG*sR*r7d z{UE}kE2i&5Fl>4`G&*ip&K`tOKUY#|cf5e|@M7Q8{R3%L^qRCpod=@h4_NXWE=&)h zyVX2|XS1jNK|*W-d^77)qCgFnu8y`r00bzLC|Kp~Gm( zvg#7p>A_)K5)Q{KeF$ENKVpv)OKVBsPnk#TF%@Uv7(AnrDQsRInjr8f^bXYFa~a5{ z8ciP5?I@!7szGH;wEZYrudRp5_>lb=%KpgAOwVKJ2>Ct?9{5AW{$o&)fX~>aQZOd+ zI}R250#pW91jnJ`fc#E}WsHQU3+_C9{uO4@4r+(PS?WcY$(L&7BA=)snP6&I-Q-2D zLluscg}JE9mbWX@RVJL8orKEeom9q5bP}EX!>*F?r<5+HKzb!*4s=r)Zz>B_DmzxeU!8)D zy+5Pcr_n8zCYf}!`4ohAe$LG6Q}Eoo{UqovEMGF&<_nXJ9dr6La?kmSY1^L&pYsD5 z4EPgqS{qkIQtyDlaFk;q^5{=wIQSjYF@Is<*C|x{}E>dr!Sqnq^bto>u* zhDW_;(HDB2!^Cm&4bYS60RlsQVc{sW(PNiF-+sc`PI{Q#$n!j=%xJvsm5Llpzw;!UJWwB#hZWy6c`YyV)C)=~0BMDL1f%!FLBTj{Th@X6xpDud(y2o+eUxQ5xCHk3ix zgc!57JEhcSsT1#-EwXWOJbVeIRl*y0S*_^H7(Eu(Wib6Rj#|E~ugQ>6&+Jb@`KU)? zLzOnuz{mn2FCWN3o8zzxOH^ zDgA1Vl;t{leU-Hu<}1nAGgPL&*t3nn-K}O%>e5K=9k1Y6tnPLfwNaTY)onZCdCU!X ztZX+kQM=7v&ZoaJ-}M`)&$&HRp$Loa+${N9oyHbn?OORa2Dgf^cnZ&9(EcWd)Z~K< zHr&MeuJjNC|66FV(!&yjQ_3y0>eTZRD0J`^LjB_l4948X5EOhH8Na=xGIhmgmn8_G zyxZt#8wwZ{=9{rZ__u4fyaP-3T;Zg9g=ReuiHY}JD&FA%3mmzFrNg=s24nBSP4C`? zO`S_sCSJHdQ-O&}@50K*FPO=$WbvScd+3nsUul>O$+Qx5>M>#~#%S@FcOT(5&Fu|A z-S4A^-PLQDNc_Pr$J}f*TD1N4HC7BxJ)V3!axU0K;CKiN6h~OxY32hIeYdKHnXOm& zzP{`M9MddZlavx>ac)FED#puhA39ZxMM}FG7R6!6(Fm7vvLe;2jwhjbg8r7uxKVyh z6p!OCd{I@O>FEzq>jjM&6h1_|w`ijRHyYL2;zR8oA;S-CHFQ=Se0u2&J`^2WfEYN} z%f*P}NgC1Hk1)@?_)NpJdW^CA$3Bu#DC=`*%1C!EC^H|U`fK{jq&P9{8~GbR*#j*m zjt}KqmvXFl0xbn5Kf!#{3OjuXExjb_pufb2Nh{PqDC@R)S8rHdSRj=za;z zDIKRWO+*o1N=sFa49lLvL9ZuinAcBHBMTl-J7o;CGTqKgh=y}q42=Gnh1QoM9*53j z@TwHuqUK@-zm#Dgn^1<4ZFri>)DsI zLq{muq%!poAmg6P0NIAHDSw11rtfovO?@hSjz!th=U9=C-yy}@iE4XfA^y~451OFY zZi|k(zCc5p_A;IJ0+$eBS*nbQY%eh;`(~?*k@~$v@e#+F>3Ym!rmUAx;g`ou>l0`> z%PTM~{$ys@X^Vw=NoMd_X7D9|p4PvDgT6kmVOF2Bc$5EY2*zL3&_7)Oog(S5%Nn}J zC5sonkV0*XUL%5r6ll^yZ&>tHvm9OS)|LO#lO#Rl+JEUQlD=`nm9`QUp@5Y)U7C3Q zEmtZ1TvBQa{Ed2tYaNwy7|`(!I?`r?Vk5r_ie32McNKu|D=3(yA2E$DB6PH_g3?SZ zF3~V1p?oN=JyjX(3ZJ5Kql6MAPF17|Zb|_4!lMr|RhKI)jg}tZKBt=(L+KBaf zSH?&WbXIRijzblZqtu{Dk1<$-kmQ`4-mZl7W*#!V2Kng}fBH!>o>)*xCbyFEj+khb zptJZN{_3nG$GItuL~#g%>u$=s;%TG=p%fEot@=jyKzC@GRFjjkqpW^3{|Q`vO46O9 znKtW`#^UW56?o849X$RFD<`QC$wrEBQ+(-`4!MHrF>P#UHBoInY2WfbK5u(>R0DMGT9Vzg6g!0m_;rP;H}v zE96d0ZZ<0QMelB`U`e9YlNHqTfPy1EnC|DHG!+HC7zFgP;=tbnE!wv?C0Ui~6k}4l ziZOjvP=yNmSZ#bB?$OW1((-;9sb2kHuH)1^1z)y^u&*^~7tLsqs{>Rfgt}W0e}2i# zbRJ^0Q=SDzydK6(lVP}AllS(HrTLWMF2$yfkU~k~vr#O3+p07Xv+ymZO$nmIqpd#F z%?4dBQza8l8*IvZqWw4tI*H>G@Oh0AMqhg>|0lLim!PM(v_$^apvcNF3J**Hf+(dj zTHbprgSahLtJI3K#BDCNEZ)unHN6yk&b3n(5=ggqp!sKb!G`I(nK>(y7w@H6K1v9M z?z8IY@*XQLQP5r<)c#TORj9%bgZFFx$E9<^5GCG5|>(EJb|UrKwC)>t$+!Qh)*w6?l*`p^$@ z-<{^9F@8#25%d>>(-M^6Lrtln<{5l1YGdmg!Oc2*;}D8GL#UHs$-nri%EQ zQ|8*Q;Jc{W0g$$FwmIOd>d%lJ)4nToZ3pGp!JNkCgKN@C(9nJdAH4S4> zlzPH+LuITqKvC+5oA^4^S>Su(z%2$Lfl90>zr$ceAY!)Qp6n+6RGfhA!!JQFw=fXh zZcg!k>DVCUeev;QSGtkN#i~%v{~`!MP*{xn;stOck{0yPr!snnw4wInN+kRFzGQ zF`%l_Lmb9eCRLU0q6Iz~sjAeXcGX~P=b;SJl3^Er*eQ1oe^x`rKEtHV{)BJgFiVA@ z3yaYz(@t#po`K`bxQk)%uG>Tn6C194Bqsf!VK#&-%|*~pDii)@ppUJN@`g`QliXYo9xX;c0vVGCVvIJiIRT2Ne8Jr}_ig zPvHM?M^GG4mwKEiN&rFDC{Z9PqEN{wMDpS1@5>$n$9*YJ)VePTN&NTaZPH>&q_h~b zBx3H!e3J^miZ8qo6bOA)N)mxNQnnBx31sV0i2NWovoDJjSoirhrK){=N9E4GBvI|y zmjfsL_N9>;7d_(6$9zB3By&Cly)_p?#HzV8B6uwnfvC7>(N2IsnQ!9on~!L+xXZR= z2==$tN7OC0L->fywx300+_60IIKxXM|MX5=x1%0nbM(^6est6>QTt`m-Cg&iA@lG= zs;IbmO>7^Rc-`5zlk)N2mrwnC_a%2=DMZ?(Zlrm4)Bl%9T+nTs3i(?n_EiD5GxsIi z9U4-^l~~mIef%IgW#6Sp?9csH98WlnsJ#+`_tl%Q=f2wYQ6+-oI8sj`>Wir>`?P6# zD+xj$%Tpsk>J2EmG#}@lXNw)_%8ivHWQveeZ4A=YKFO~k&>Do_H$0T9Pgh$$z_EMe zL8{Sd70=#^U7Tb!d4l{H1@a^aUnzdM z@&ccDol>A?$&S*ISmvXpvx0NO^R7#N8+!_94A!Hlq~z?1Ide-cqv+lrwz-4?O=w_E zN+P8~KrKzPKg(WbF3%xTrI0D#%#@{B@U}t-VY%t|@z^UpR$e1?Vw+fUvgHp1VYO00 zzl^jV^Va5HFeANk{~AlpZEpqqGX8YTFIejA5tu(W!`J+7A4lTTnnbT9SC3O(CmOb* zIE814={wF&n+TfeG29=_dVWUUS1QsgF`>d{pzN8hoor=2kIg3y<4tX=BcYG~o8=^6 zmK$m66qmksCc?wV8>5V?U*v)7hS5ye9P@c|7E}5?)|%^e4-}7trq_1`X#78$K&!?SO4ppl@Z<_B+5;xPj3CZgAJP4nL9cuf6H)% zB`o%snR;BD@7M9o+P1)zH-Wq-cGs4C@hB(BX>6N6agY}grQK+DczEIrnHfSRMjzg}>9+%fHduO3771vU;MK9oGhxX|NG+3a{yHLp~gPcWUCz+8T-iB{8nSz=+Y(d)sH^>)oXY1suS zkD^?~7tf#ZqG4WKYH`Y1=5je5H_JcLZOohXE#zG(S7GjY!=qG2o61uLFJ)BFN{g9T z?I#{OT*Z#%*~WG6+vNLre#d>GUCaK<*K%edBzTqxzSanxO#4Toxa*$73Os^ec< z?AIk8w_9s!%bw-EBxUV5Smp4corQ8@nlr<*HPwtR`k_Lml}?3$tbgSaY`LB#UdwDM zo_&I9R0PB=3X`1{!hKv<)X9DJ6Mx%!lvd7*1|M>$?|=3)s;5UUdFnzm!CKH zueEr*(|7#w>dd{e@iY+{6JM9GS=NjB?qkYt4H+bQE6a}&dx?c-R zVk@<7Jcv}(4{Hp0RBi0~_`^WyoBT1A0zE<6=qVA@6&<+{4^m|kBhDQ!#<<>h-<>(p zq-^NOu#rz}}D*>ZtA($x+Eg+tb)+3HK$m{_&a2vXlPYN{QM&;n5+}7j*oe zi3+SYM^Dj_-eGo_v*b|<6z||~=T~@H$;K*Fdy-bA(TT!ZWLn|@MH6@PsO9F~wJN`E zk*~-3dEe1GjCKe=ePLuUYs!@~+>jLLLdV`&+9IjKp%vJ4>bqgNq6B^JABEPA@v{Co zEb&f)U4@epdvsVW-IVdRr^jBG)lyTNK$~VK;ml;01y+eR(sO~-MxPG}#Klv?^a;41FQ5 zd*9MrH?&pfNo!>kzghHrb?uF%ko5PhY;1DYN1tu%N*smoQ@*BO+MySPf80&h)8xsq zE$W_eri;!&Kl(VU2@n3CEJ-pT4?#TRm^?nl=8~ zW*eT8Q?vU<@$AIIkFIdOsl|KWZ@^K^y*% z!us?C+A_UvlG* zuR8ZUdB@J?=|ZS%#FFh9Uvs`Rn!Da)gr~Hs#7I0wm(z6JV!%xGhx3SRzB@f5^%hE+ zoLV%~hrQ>!UK;k&pYQENdwPHJVzZ>mJUX!urjGOLeYt3QjN!f7mYXc$6uQ632Z#oYJ8ksPY|_!jDbTv zz@>p==&Eg9dg3q>;xdfM0>KX);2jW(rGzA>+Y&X{mpJ-DOWX+Y z@FXel@KoYX+H%4%BWQA1WCTr*Ei#+;r32g38S7-7q(oXqlo7rOAHPH>XRT^Vmke_z zcMjyC_s~T`?9n|*I>tt}%_E-X?`=JqD63dcY;{xJf=@I}zrG@InO`|CY`UeTwk~ku zb=`}VH@*|?=l6DYiEkgNq5q(;c;8O>XQ=qyKN1o&7sa`!Rhi$_oCv-nM~^-B_?-m1 zUE3WRrI2t(rMImQNTj}8{4!L;q2?sd`J`E&hf?w)tK&=(MO<2&gpg0Uqltxzz&rc- z)>R8LM^-2QQy+8^^DZhe9{=S>khc~R#cQd;GwqTXKPc&!82;5yj_&RHu~!_KLxO0J zKsZF&WrV-b)c5^W8v{1a?}d48*qP;JZx++0k3;EJg^ALF&kZ_`2UZ)6`n;2P#YX!n zIsh`KI_<1GNND>uwbFh*@aatIGKGtLoKSaV+CaN~hqy%vIz{dzsW7nsVMp)13))^W zI)=uHIf|rby=>ERtNS0QZ+n|mCTixnb`LhRNShU=hlH}tKNcm1(VbN245C&aTRglTO)U30J04L;M@u_w1h8)udmV@g`iEzC*2IvPx51`NN{I zut2`deynmm%vZOe$^E=iAN$DV8JBG~^9Fw(!=B%FncAGsy~*wcM<+u4dl8==PU#)L zq|!)8>a|_4Q+86VbD?aJ^iD4QjSqCfEmr5mXV0$6dsRoXNbVNCv0F&>bi)SsXDgDu zx#-1h-CYoUYs=jI(UP@m+4)HKn`f!F?w96h^D87fDVE(Kd(-H9>_*9Cc!5_q{Z4b$ z9QVjp@lN)n(+1xb;Z3qzGe54p8Nxra&7*JLC#mP%%;yzYCcQgBTJZWzt;Huc(gi11 zp$VfiKg}XtPz7`^zunLLAn}YQ1^aPbs;D8YTLu3@m=boke51^|bN18gVU>u}As)A>*-CfB&zUK^T>O*qyQi7RfGkpK>zT2vT$Rf= z{kjV#0!r06(Lxe&YW(mSS+wqbP4o|{T#1u)-QB#Wmrju^tW9)`Tk*-&sk0gXebMW9Dru|0lw@PLs=$rWVWY7k{ms+t zDw$g)G|7bb&Uvu7jH(ZNNOe&qF|F(zF}^`@B+a~w`7);Q+3AZO^_MW#-P+R zDqe)qWJ(5;zusaSm>EAjsU~@)J=w_VbFaRdY%k~So=ngcrY*{#3y>(C--~)d0uQDw z{UCF)R}rfW*P|Ss8%_re^M8^K3ScUrGaXWUj%Q}fV`fid_Jl2M?k&c>$%;a?kvd_Q zgkdbZ{Bicf$C=+!bDGyp>LN{w!~^iLd-vFP?vLv*yf%C4jE|N0B;#`X+k|@gi;8K1 ze*KHoG}Z%J*2ALA4i1l#-6*009#B8)(C)7aVERS;?8qDJ*Pf?_dFA7$pUtB!w+YEB za&s>%CATVQKihV?IHqRc)L(h`O^g6pp*Mb?7xjpCdT!@RB*`B6|JG+3W3A^f+r0#IufYs%GUw>e^&b!nr!Lhx8V4u8Jr`;cug zO~>gHex>vCM&oCFRs8`b^Y(;K2cfsL_ch9_iuznHD+ibdOl*$1?p?X$cg)-iJ~ITh=9FobQ(HPHwca`=cJyO%JF;bl6yi{#@Qb5N^-_zbtNtff%vWz`gfl4d z%`ws6F#14~*=Q7W;`nqX7H`&}Bx)Mf&a|P9M^4Z|aP`Hcm$9Z3-s#m+>hE`hMeJLj zkiE&Cj1O+2S1O*Y4CbZ3Vc8HzmTtVtKxjZ-k#4kVO4uo|l^pz)Ua4eqLE>EOT2{yd zmf`8-r&ji_?cY~f3CVuO=kk`GuOhl)*)k&D<}N+V-Hu+YqKf(y5F)FU>(yr^!F)$uA?MML zGc@B#$rorJ-T&6*uI8rmP5*U^E$K9-%8kv6dkNFhEYP7-^EtM@C%^lWtH*FZkIe(B zvolwYOIHZfdS8C${&cZo8tY$FnDw&UYVe$6Qkb=HrkKqeqfyD7>cv!uR~c14)|bHfQ~gZi`8yb1iI~SO727|eEevPa zEBLc~R(Fc>rf;!_WuJ>nF@Aw_|2@ZFr`~;vcxmOX^`w8f!Gb{I&6Mf8(?Z(AgSoXV z+cRxRSN$Km-~Hy16LqEAvF*%2u9e&NQS%@EIT;1)9?dVf;^Q^G`<3Gx30`j6U~q{EM;Mz3 zI>b`7PYrwy6EpEO|8?56__KmdBVTcbr~av!@N&(tHpd&*jlQe4q>;N53QX+3(j$Zi z3qNmf1w|b#+@d)LduleutkE%?XzXOZz;L2T^x}?jW67!;>61V%L#G_9a`+#jI@2}9 zopk#Z4cD&h zXuXX}KGKo-GIyrCD>-+z3tJu*mV3s3O6~6G3jxDM>{?iatmpHPMm4>lqy&fj&-&Sx zlD?mYG>O-%uhsa@D;Ak{ju)esmwq_Zw#Z!96is(5zrH2lT(!_R(QgxpGO7Mn#n77j zqYF(bbnki9@|*}Ath83hy%v{1c%_XqxhNm6^4PH{+7aF3-hnxnE32^!KdXM+u)e(H zW5ZQ-!TR#43nTg-?6j_tA(5Ryg|dp*N5+)syEsxY&(hpnqC@y!WL#?NTcGHcatPq6 zLls>AHp+Y%j(LNA#49-6!37_t%%KWlQB7n0cOEw0T=;Ge^`r zl`4jpr%Py@8A2NEED=)FgS}rBQp@RL=@aAQPgN`Zl4H|wEAy+vn~I9j$d>`zL(Be7 zW19kDyA2(`Y<^duQf}6CubsvYaZhPqVwr zl|N@&BzyjR$#}YA`a!;5(ZVf9x)}uY__cCYnoTTbLldhvV`AG>)k3n}EA_QrDY>7tmLX#CwMM3ESGj+0do*#{*^!Phao@-?5odKyNtEE zejJARpXYY&_M)b@%a_w$Do@O3=|6eNB;J`q{(bId;^)=^LHX??4&qd1SW5kujrQc- zXV0xO!0!js*Z)k$EP3zPQqr#-)v{aBQp~ecA%9OXXB7P=c9rtVAANeSj?6~}_Z7E| zni)zfKXYeCT;P)nI`uG%j<0y`R7+x9tbywMDSq=H{iwO%);{fGKYNo#PkN%xHoFa@ z7=QA|y+*BH6HM~aT=~Ya!J^pgdNjQ}e3$TUCdN~x!DHp#Y>K`>=5wtg&3Hd2x`Ovf z!t@MEL1j&bnn4#%w~2||Sr62R&N`wRyhx!}|5N1|@6XcNxyg#e<>OX6n;%@h3#314 z*!p0Jwkf@I$)1Q#LEO{6dvP-R4zr|J|8!D(Lugvf9CfP`G4D}z!^JZnu^g41BSI-` zsn@8Vyq}Gy5LtfDGaa$~p0nKa(#MZ>-;PhEiReA4%O!TYNS#}HwKSC~-Hf2onkZiR zH}$1-7KK`3tLrsJsxPAG*?;OO1yRg)jl8816btK=;_5n?xA@lY6$_I+)uky+`@82B zVVm|mKPBvcitGIBWs{xM9F3aB)`Z%4H0q3oHC+w=TJNfvK~L3_GcrGGR70g0o4xR1 z8qZjae~p{o!jH*dzWv#g#?~;kj!}2&ofMbx#Yue*RMUT+o4(+O%w~b96SFJQTiM;bZZ~?q#61t*VALRfN?AjU z8jX}-y~xgbDyb|feA_6LI7v_oOWi2`d*N6>ah!NS(u0M!9!k0^X%1njAI|s%Tdr|0 zzdie9L+XmkohN?j53oUZnOzDL`3dmw$iR6_9j_v#-hcng07t4ge0~&7 z8fVyu-1%2nH4^N91F-u*w*Rrhy`_*4_bosiUKvA^k>S4nAos!*ww*DEu44JqeImr> z=7ga43Q{D_RJb3b3rrD@83VRs8>aiP#}7Eyic%}23?>X-t~ zu#TYBvzs@C#_$X1;xbkBDQyixkHy@mPFZN8NKi)WtcPR{jt@KWc_)Z6f5S)LgI(lk z0@`^|{)xn`(+w&E5*2wLANmW@g=yjEOw_nM+*IgFcO#(k^{Mi;Ejr#>bI%WsXr{ZT z7(Z@=iOH4uAsW%_RH`M=mp+GWiF&@~)bm>HRy&)J{iCUQjr$av(ILC?PM_aoRHJ7; zmSF_BSVtR=zZ;*R^~O)Q`zFy-NJ?!b_*zl0>YU4O`4&NuBMCqK`NE9-q!udnF!@Y; zIc%TGoHLi~1Ov0e_qIft6(pDR&Oep9l=St@V;IwdFW}Kxb8RT``6XRPK5XySu-$#1 zTS1he-C7k7g{X5wIfgh+XZkUYET;y0zsXqrP2WftPm)M#cFmdQ*=(t1*KWuQDkl?I zyEyAqc@V9o_p{iWXknXoH%|%DdwwVS^7_=vkf(LYD-S<9^nKK7Ppg;z+8&L*UclIo zozB;nXD)Mk^z;PYe~Ao|VgIX?cwELJEs{o+i?RF3s=4gHpH2;{ar@u1x*f&g+p}nz z|I#gcoq1pX<_8P3pI_3>5C;Yy508-;5AP%{zgB-x$FXhEVofd2(w(H<4HMF_U?kzo z(f;`KuOWFEQ`T28mE^8Jq&nGpe z(yto}y)R{cN2`Xdocyvr>X_6j=P^$43V$l#jsN6uZfDWwjg2qQ<`pcPWZR-=`!!=b z^K+uA(t3iLCG|cJn1P59hBbuDbMPEBQQ|jy=OPF5@2% zu9Vl4v&i*IeL>Te!gp+P(45zVN9|NUM&|xi?r{eR?;qpyf%=ofH>{iWXia|^uv+pa z26=3}FLlpgxJ-mCo_ZOie;sYnP#7dVDjTcbs;a0!5v4ugjnC3k&aXjhO>ug!TRrSp zI(a)&(_5jY-a?LYEvAoBI=Ye+{dPkM4?P-c@zRTjDmWHif4^~VqrFY=e(jDwhmC%( zcw+mGeD!Pc+dT3?aeI1N__1Gi8*RInzF=Pj$oluC)O~Mu#{Sue=ANVJnR`-jd#Bqj z_F0@)hExa1yj)W1(TB3myv-lAW3o>K<($Y^rl2t%Mt|#lAgS)crl_TqrlR!@y|GC) zcf7^=?t?|nw*(jlM@5?Jaj%Kr5saPA(?ln`-xPR0!Z2*~`wP03AWA^(iYdoaf}iHl z(T9mnn!mZSuFyQeR3>AjL=qr72bL1uAI!WYAwhmT^V3V+`i zB2JTp3NR=2@KRN#+_BV_)N-@INlhRDzW!>4+> z$|MieBLtLn=NrGzc0XYf9e-9XG_hbQK=TZ|@cpUV+*{e6*z4b2TM3^)4c`s`@g%Fmko|Ejtc8zM#0725tE{|96yG1jy$T32&r3>;p47QGgO`jrRQmf(SC`iBTmYd?kU`{s(moKI+%E!H2s`;K> z)LNYTB`~md`{GEeMe$-yM1X0<%=NXv{%hCGtJ`k{DQJ0-C!Px`^vuIv&wG73!`D(z zblS$(MtCLOp0xOqs;u{Btm^qDfeqg%auePnp&_HkJ!dWtwmC@!nzS%;yXaXKIz$Op zeY~M#(J@Q*jQT+qzI!Iay-iGNJG+R9jKI&h#m&k4Oy5HxGh5*{mzndD z+4MVdp{oy76P6ySE6O!@SI!I-%H(@dPq zldETmPG#IghtT9gnZ`aO*Gsm9q30&dGdDPyM9OsS_Q+hXTr3mF=^i&NBzwk_lKv(3 z%XfzD6Fs$8yc;!tNxA-V!6x`f7gpwH6(*}KRYhVvu6C6QmA`s4(q6e-c$SNdrsIrD zT=981rpQjKa`~*Uxz4f=EA`AX6I%?b$&w#cQFK&pEOPqyI`}sl^}S1MxruGRu9U(k zTxc&pO!ukngHJ`7V{Z7PbHWQPy@a+RzwelZrN7`*^l$X3h>%PuqgTWV<~>qAcd6w| zu-4_y{*Ki8pV9H>@xmNtzhsr}d6N1@m%1e+B=g6|q-E}w-XoGS48@bBup+E+!YgC0 zX8ip0Sbkk4-I(qudYG!qS4~Nrie`@}Xp6Ow(NH1yX|^os$ZkEA>zBp`FrvBvh&v&?rps1 zQonijz3qoz>?b{aDKiN}!UyM)-?MT`GUvUXWX+Pyf0E#Ld)TtuGG0g0A#yMOrDE(( zV=@(Uwio3ON$1bgj8+*WU|3fErj=@=tvdrv3tc|gaV&wKr z;96tE3Xiww)IxGXAaUYoZ9$gmZ1=Wc09a9aBqG%t`BTtY*Id@?L@x6a=eJUIsgdDR z=lS^>SNdi#+S31Fm%2b@RR%lMJq{j-@%U}9&_t7}O8a&0=w;|m&Fx;PVq>Z3Fz3P4 zh9lXY5m-;r&^8>hYFXH79x#r#h3v&1-q<*To}rq<$~x;l+dMOrO` z%*6F%HVqwqJoMvAc72DnwQTjW=^nb3dM<W!+#jmT5ascNkW z8-Ht>s8gdDs2OhD=G)>E;P~3!?!lX48CSV|Gw|b!uj6}lUsXEOYR|n|qQq-kt)uRr zvK1Qd_^f;kd;Rn4ldq@-hzk6Ktq01y*{oNnKI3n3Fr9ecA3pRly@+M-H;MI8$At@{ zTOT-7qEl+NNUKy@`tt^VOIbgDusTFNJLzS!rBq$_g7#yHN{HxWX^pbj8b2+(35qF#H#}1#$F5H* zqHf6EULjolgLjL%K8^Mk^IO|3nx>5lj3=g&mS=C>YW>X4c;bR*Nys+$j!lMwD}UMR z!tN*8@ind_&0_`euGf##_nMpuauHXS&Tb?e=6p#*<n-0) zGpXjx23?q!EBmklr;cybbPS5q^Z;xH-_vrB>*_tDoSA$5^3_0v4(@fXZ+6FDi57*j zVajQT>$Pi6cT#YF${$I(-RD24Fjl^iT_5%84rc|uaHG4l|AeNR*B1V}LdK(2F9Qib z@^|+Q$DexOlh=ce{9Pci>0;(y0~f_S^n1Tncm~7ndVu%WChK zdp}R?c_t0b2$OFU3Ml+InJ_DPYW<~j9IN4dmC$~*43Vs+c=b95XB(e1hW=8`K-c+C z_?hW<5))1Cdtkq%4a(mY@z!qPex|RiqsE#Y+TZIcpx`rN7+;(3FO-?$YGj&L?SHGH zowZkD5=`dO4WryL#GEPOPD@FWkqp zop#?uV>#0MY=u;sOnqx&DBZ^r$%0=k9T)ul!^c!}N4%A>y2G|F=O1lkI27ooR)z(e zkI64AY&LzW?A=V}x25gS*fPD2CH<5vrQN5yU=`sb|AXJIGIjaxM>_#1mnEeBS6-(v z%Td|n!fchopYuOy@&p_B*Zf83w^of$-fJ}Jb@#Y(g~>u?jXvsx)QwYZKdT>SS@kUQ zUmpz3PZxLiMuff3Wa$%hnX5IQbGl>Rq}(wa4+QP-cq?nmd&vVN16 zICtl?;|^sVyjl~*yGl%ojbC$8;-BJ2V;g!Uc3VU1TKup?E~K5UTVR3vxn|*=?YLoI z8+FSaUZq0sy+@%Hhbkf)>uPH56rHw6eUA##^krEblA3iGc=#wggVcGHg%VL6$XE<{fzSs0QU5nz`G5@gcck%BPxRhi>v z)#|WPn7;qEiTHK6w)cE|0w!Yg7rj(%^Ge4l4b#x~oR3^vD;3=yFJ@#>28Vr;ktV1s zNEMS|U^n*8HK0tfk2bJN@Nvz1dH1HAL}DVzW?AItd@TR9wMM<>28#0*_k|npsx*$) zx~^Y(^UI2N-NAj?oEGg+c-`A>g=lOrk9i~ALaBf^PfayQ#voVP(N9+pno2B)U3Z28 z1N)5n#P~n>)4eg6KbQBaw}e;dB^BYv^es=_pho%9nLK#j85+A`HpN{+#+xae-l}n` zE(gIf86>TM;&%YDzHd22VQ*nOc&QGNmkuu$DESo_mso3J2;z}!C+olIZtj3>S zwiAzelcX^Jq&RUm{?8(nlJ0HpHo2uCh0ovE&98V%=g3>1eOTfBsW0BfeQf0$Tk)Is zeTufP+xp@=v^&ElmGrJrC3x`EalEehAtzuJlO+-9g3Znrg0h2~s9UpI%f1NZDw=sS zN=KWfG*Xm*i?+YS_#?V6wo#}lz>={dX3(}S@ghs1_V_(AYMyKP@5bcFH|5j&TD5<`?6&tonP46nK*kF$*-UHnUtq&CID0Xvw&E_Td`-4z&^yg>&7o5rZr)T8b zmHWJtzXkr5LQ^-EK1_eB@&E4aN@=BVNRHvXeIkp$|3CkB->DBv;UU7!| zGZ2%r9_y)}&VIbQ+Dw=}Wvt}1y{4q|oBup}2kaDZ&oBMhpJ$?-+WhPje)~&+=w#NM-BA z8$Y_l$P?;ZlTZ59h`%Qk$+u5b-cDk)!P2=7Ilq|F)Yd9n6=SkmAJ>TXEn8BSUAgS_ zYU*$jNrC*xzoNp&X|xGju8)iY=mevW|Sc=i^S#HpmIoAIq!H#;{zBEl#8u zy8}J(nVadn;Nh=^|9r??ZqwkbXq0@H?wG+-w@&*O((7MJr6LKV-5xddeXjYqUSq{J za4p8|!E``ElXvm7!o;*|E&5u>s~`>eXG#v8#V4n*#aF|}blr}W5lJ?NCW-btgj$5( zoqNk(#vV2p6*YL*sQbR)`^2|hS}w8MYXK<>w-rgB{8W!mQ`daU0-0!(xcM$JQHM0K zf7y=9vhc2Po(WWr!(9J0_%e9VzthHY5Pw|xQ~bMc4!LY9f%#E&^tL-zOa{E$!P6EM z@64E%`LHiL8gpXbJLWUiDqoi-eEC$j%hn{q@UNlB#l*X@E`wyGPv{c#@I_8&8~ z&M^6#O%jOYRaH-N?1oI9{_kBG56{q2MiVbQMiK=c2t4@UApj2{c!h9_vjOd{Q4ekjY#!Iv^^s88qwzvN&EqQ z9+A!;&{l|i{{d}?RI%3tTuL;dc@fgO361>H9WH1>oBUO(AyT~=ZHLI*X7nXQQnsKk zBJz3*+8L4KEofUrDz~B?5t-eJvnOf;l>+S4hBiech+hnmt8HjGL<+Q{l@RINj@CeA zNjn<(eLK9cA z3!R|9fGVdG?Sx3mF7$OohIFC*5xMsldv~J)5&XRy9f8POJ?Icb67=F^L@$nK{Di}) zeB9Ed3>I zhj8uNZ_m&WTK3>K`!Mq``qKU#$=@Gv+04swT4Bj__6 zh|xbk;P}T#vMNqIj~|9d&Y)*iQ)E9H1ZEX;9<~mR0;fG6fFe{j-ihtoE{iJsJ8h( z|NEuL;)+{{VBH-w+5Tnm{vbn6ANOs*=L`D%7{1<@%~u9DMi0Ty24((<;n}`r+|fP~ zSZ^H7g4E(N4r)>Ugm?fv1N?d%7f~C+w-4|0t6wQ$<_R>#zW1!rI(=UV4^Io!pz)7) zrjh@wGT;s-E(EP3#_-BCnqhwolH?^SUV<>n zz#adof7}}GTgJt#lfq_S(Cqux?yrL1y#m(HfwkH{)~-MHg8aO@tM2p&U-VT6!?6_>%^e9~|xgb{%g5O7Tz@nHeI+LyfW zO>zt|th0g^KoP<9%V<8BS{5RNGZ8``M{KO1MNx^!-)MNk3L=KpSAm~y8Kilq;o4QS z6x1Y(06)lG5f@Bs{Fxo5YATk%rzw`z;oqV%7u%Urf&Y?)) z_6=Z@d;SnD@&hda{c$*8nBepuz$Vl2fH?y1`~XLg2IoVJ^H20CsNWr7c;WM#Xm(iM z1H}TX{sE!0Zi4W{Jq~pG5Q#qyoC!d2!@oCyd+vb0%obV;lDL5bueZR-X6z;obcCZQ zU=b{e9QHejp@2E)F$6F}7>XKfU%3CWg9t+pnVN;6XkbCF|4fs@|1rHAc3{c~v-}1T zaK_;nkKZ7IwRjvD{|zFDOT+=aZICI)AN?)34H|qi1*X|SUx0|S|Cey*YrveY+(FAi zk){8S75oE^na|4pVHx0(Kj0{1R{8%}fn9K#qpSXhWr6E=L8MhL{$Yt=jy<#{6k7Km zs|^Xg2Y*W>P+-)ctVZys7i8N6gc4lc4Dv#N977HBpfDKdWGj3Uh4F)af5Od)c@*Xp zR5^?QDVS&!MUNZ6PzcyIjv%x*L_Ld071;eN$WJ?bi~#gx0mtkuf*v1182#k~h7c}U z0h7s)0MO4?5n2i^CBW!HAJ=d|j1Z#%VSnPlQ$ma;^m7~OViEYt9!OArB8(VB{^t;L zeizJ_bRyu7YxjU=gei#uW4O1^B&0(0uqY8|W)v|9y&DCiNHNmz7%}J&3jzcvz@>x` z5qyIf*jyt4Hp@gfx|swc3qhm^aD#ZrVS5^|lH4N45W%UW7;|Xz$iEB^tW5?2T%|rl zE73w2m|_!Teh(S&yhD4Sql69VL9O~^pjHKPpj)Fm&}l$43! znAX67R$7b-#G{P^t~#I%s&v3MM-Rt*I|FgRb7KF^{&#es4~z|PI@l1RJkYU2D~34Q zi5{Z>?Hc1iD?LUPk}yR8GqTQ;z*o&63iweY`tQ=C%>X=VnEh)&1V=D{8Khx;K<}^Y zj4&x9ur9DXpjqHwzroNxwT2F_Uny1x21np=YY-(!YHGL%DI9Elpd*IsY@lOcO0kf^ z!b}(r{6!lGUONXJhkckZ0{Eh~`$!D#Wx@zTH*FJ{F&FTAaHJfZ&Wz!Mc+SDi%os^X z_Z<9(8MNBx9L{;h5G4t0i3a^x{+H?cK}i5VVa2e*uhC#5{`QyVu!F$nga)pTpT`vi z3;}Fs2l^<76@!7TF~HjSuda)kg%G}r!SF*Fe;Lsu)I@MM22?csm!YoBaR>7 zvTr2=ce;YHIm!;khTQJ6y` zfr!Mw*&G-dDDn;t{6qljT^!Ip27p2o4kRA~E7GG_99TMrQG!tMI3S+@mbslWkmQpm z!EWfn3G&1N#_1k&f)24tK>!+F=LCbS^%w`Jc`&4Kcm|j;c3j9vXC0!8xj>v}a}P0O z+!!gSsOS*0R18tWDWRb8!Q7xi+p z2FD73uAw47V6>rh>H|OqPtxF%!F#r#SL}{~a?XOF=gsN=H6Vb~81RYVq&K*PAcWrw zV$jej=0jHaLLjleupeU13xRc@g!2$nBZN5t*$NzD9t+}w_fKIEGLgt3`nE6#xkUoU zbO~dWA#>RSKm?15fVxJ&85n6JP!qvuWqfK_*d1g}o(PCP zI-!dL5uzZSG{LD@6mu3Lw?ZTrEH4IzS_~Xe5fFob7cMyS2{F)?k8U_XdKsSqK5q>w zGZP1u5nV-S47@6VA%q`@gZa?lb%@!$j(-Hce+O8TN&xEu-$S}tKM;1hBGAd-{AWb@ z!8!H7=VJ*F>!sTVj3N{gvJVoaz<||<0w1r{fDboG;J@?k|5W4=AkaD~plU@_GqL}v z6re@RF0VpqZpM}M;@d;p3X%NR&)&WBgdq@MD#DW8c z6n-rY76-es1BL|7Ctve|5yLiY%B* zU%C#_$+Ex++t4A#b{K>nunqRo{cL8E1D;Nd95TR;;*-O6av+@5@dKI&7Ma9ngo`;r zSKXWWXC(Z;;H>QAL7Gv@gT&jLKVVKmTT6ePtl)FP6Y@xxtsO7~FuwxG_=i7m%&Obc8rM=OE^ zdqIQ)Gm7AZdzKsrq9_RHVQVE2!e>ex!$M8Kj9X7zm4H(tS{xlgN5Ba0PJ_A>nFtQA zBZ7=LgHmOX$rqHt$*L87z$ieDY&ek4PCy59)c?0)2&e$x-#KtPK~4e;(vN@pKN8VJ z@Zxmu_y}0xaTO3CjS!B}6(&H#1_dAz{S&~@UIa%cixRNF87F|@p!k6y1k!bwHL9QylG+ChEAG8*-&*Pn0X4iBgCT>s^>7BZ z2m^YM8oqlHc#1N>(RC-mAnu&S0hUvklTelo4vg4>4*qrl6iB-CPfy-;#2Fa+5)i^; zr@-mb$_>Y;s)1vi{*?nY2^@133VQcP#4%SR2}t3|8w5n~Q(4fr zx7ES^wG(tmr*emY7;Zy~$VME{;5HRm7i2X+V`SnEd=tXg;|cZ`hQHf;5@L`EA2OIo zA|Qt+G=RHLDTio5O^gY5du!gS` z<3Lm;=w>2qFfzs!2MiPJrVYFZS0fAye5r~Qi&P{Xaj|FTd<7qqXa2l0%CMNeZWVSin)l$iG)Vp0b{k^QsB zZ^XKP_&}!(F;C!t!6X64p{-Kj%RiA}rVp$rVB0SQjEP7lMST0mC}94;hzzd%21YgS z7_bV`19he^9n#h7AxqoZA%^1&=-9T6Lk#u|Shx*-A7Wy+2`J%qY2fkK8Q_s*7pFV1 zhf6VPc$1Xy@QnXT0(a|!&5nNA9tFxnKu2+!&L(`|#N z4-7D{To8!$uF*dReug-MQX>%PQBzPaz6p*|G$lNOTmOSiLG#+padeF-ci6J-k~zi%y5WgPZureLLSo#a z#OU`=P(;4C@@?jzXLti~fYSnuSl2BaAioWQi?smZ`Ub-^mLM@EEWk9q8;$@I=yWvB zEG&kQ27c`T0?4rh0mOoHg(b!cDgh~P+Dkc|fQ zhnV{fpzFXfS^#?S4o7R81Fr{QWdaie4TIk}(7;9KfV!;bfC0bT>jhDQt3+y;?mVc& zU;wA1m?0#A4bOw4)WYxq1MdFLgO2T+K44hka~zKqC?^fI7rk5&8mj ziwE|+2)2!y<3x10CYW9X>PCKqwt^T%aB4$QA{v~U%n_(XC6Lk>Sk)0M1COL}Akh&7 zKTY8)_X5VH;roOi;U zfkyNWG{kV16BuH>vxgWlXRv-GpF6|=8wxnh8N5u)IUb_AKu8hS2rs1AvCjFM~WnJ-{(fFM~dO9EStc9-tNa;PL>80{{{@HVF&^@C-Iw58(7$ zGNQx4oT;F~$zVWxXZ({bj^KU)F-XfGqJ@>NfcO`(VEe0p3BCeG_e(Agu;zngLSB#I z?^l4^^+Fsi_zXw??P&CpYnY?(2~Ti`F?|(mzK?1T7-eXo?f{U& zxt<`w>fa#@H%xR5OjENa1Xx2C+7QVB)?jdCWa`9$qh6qEa(fYQ6lNbM0++*H!2g+n zLrm--5gGg|AH=@p1!A8XJJKN zRB*i?aK^}hqxBhy$zW=K!0>=yJR`N*GJ^_1Fal6D2FI+h5Q7(1gh}SWF@yo2b|r2c zutb0r9|E}G6n;MhXa*K81A2SwQ<@+jQmK+FsqMu18Lu%MDoXM|>lIj#^Ng+-$< zw76HFM~LqKy1MRws*a}{FXi<@Q+QVa3!q?4KD!Z(v0$&Uw`gq9SfkM>7VM&+21c

7nW1GbHk@&f=@ldfTp9v?i^!q zd#24T{+z~0rimCE_I=ZU87O%y-AV4t`&5&KXySP%ksBSFfvMv7C582&;F)OpgsUoM zu3+liRG9Wsl{*S3L*YX;j`VNVEL4&HNF}>73(HXTmkQ%U)1%?*u)TQS?>!q^dhOmT zGB=9(fSA}H`sCTLROypS_I$Rjm6ZQQ#bmi?HF4ou`*QA>YLi{G>Or$cqTbQAAbRKm zt#fk_>$dL91V$r{hj1hojdw;9POhRc!ZV{WN$$ewlmIp6qS2u?8a@{q)%^u2)35-o zMdZn$(p?--MWfTg=izNIE=U0ux*4oB@`gmlJmmS!%PBHWu zqQeW}?zui%GkuzmcHZuxFdo!r0d^Y+`;ZPD8=YBzMpo^oFlGu|2)~jCshGT9wch-~ zKXABH+&g1~av{R@%_!l5AJzB^>%qve3=+p_i_w<9V18R9GY=J{U zcyKbtQ8XUQ!qP{TP6qySdkO08 zdr3uayo^R*FWyR>t~>QjlWU3=maVc-*uE4t!!s4yhdwQZPkpi#MoX=h;VC$JPsJoI z!z`5fM8y<;rqz>aIXr3ng6YVY=zqM|8EM#ZJXa&%GM$*K^`Qeo@xS-Xm_H(T))inz zePSjlUyChR!FU%ilkcK4(6$wL)jTfI{FOHU_?2Q&aJTOwE42!Z_wry_b5EU#_gY2^dSy{T<0x$vmU~Z`K}2y~QEJf) zaVx(XI$Z*oE(q1RQ~%XS^Ww{>n2SL=U;C1oBa}~;Q$(Ir`EN9?Vl{HOr|MM6W^q5Z9c+nHD-P-j{M;i)zwaFe@-?NqKAGS!x$%!q;KbA+`sDMeAU3&Cd*82++U30<_d}J;p?(A@pi9 z=B<_M(LIfZGl(34$lB9xuMP09&F@S{Y`}SE=P?Xu17@oQ6Bs<+fKWb~%pfodeTFUI zP$^_8Gd-ulPrUnEY4=9hyF7#GXB$!HnP>*C^K{<)-rPSCIul}U-4hg`qvcC< z8tPfEaGLT=f_B~2tdNnYbEW1<7=ukr`$pc+o1h)OT_sz(2|d5-A7-BKg6+`5XqyM(C=J^y=n|BaqVpxwY0$n0ocd0S zti!Ib857iwg93Dte2{$zvh`66jju0gbGE=@I+76~)1J`z@hjFdLH}`*>ENvh;`=lP z6Sv~Q?|P0wdbSOd zi|rLN-*3mG75PR0nG&{RH2j9_LV%p@2+5^929a)h4K>|?x(bj^2(e(|!u5_*v*SBZ zOG8)6-hp&&q)zTlpyIakwIoYmVRi#>fH~J{7rowzLW!7O(X%F_v zZtq4ea-hD#G?5}2GFZ3=Z{24i7`)ws@V0Ehpy^(WrEl6YNEBdbCkFZyRF>A2L5~!a z8P!VwnPU3swUnBIhWzx4!g%ulD>}%@efNPvp^emWFx!b4qW7Y@;|rg_Y{XT%Ih19^ z_G1o|M=kf;MPh8IR{|s|4AAyI_ zVf}FI>0s(g;YSppqe(~gI=XonmR}ray3`Tmg6~f=sB}hOl&hg5s3sL>p~6o35scz4 zmldF;ge!U@)jbM3IXL_jI#Z7#)J<*+&`t8bD@ME@HM@sqw>Sp1T@RRf_7FALw|4g& zLk+n(4*D2I)3|30S{z45xxHcV>w`2fQk47oaj_g zNH{`v?F4SREWoksc2~o`@V%R5}_gU5bUF~m?@Oz5F5W6Bw5@*>HXwuBl=^0`LTY1mp;-p&`J z-KTApUFPCsbCa8~jJSGbCI2)8aWJxb(Gj?(@`jT&0~67*F;w<#v*Ao5GcYM$aNKqu*tP5hRo zv*}n0Pawrf!_fE~WGqUR&Z35If|;4v*yu)eLX2MVr3!Z~m!5^qtzjzplk!FbjlY5V zUJ040mP!_OPNWd^Rm`tH7`>?b1!#9_Y*f#$O&Td$HR>tp0{ZTsK3|#miy*%1_m!Xy7x73K2dbFn zgN#-_naa3m^T(Fz{EO%u&r3*c{u`p`$u#K_T&Xl%Ve~X~1p3T=ruFg?a`K}iR5F)Q zMsJqc1NGBo_}XriqM)ONm(kXwb@jz zK?R$xz^Ap_6uOBNoU8yXb@>l<7|t>??7Y!LEze(UkXP;#3Lt5H6OCpP|ze_gC&>e%=EklBWJ$?J(*u(40p~D z&&)Nnvcely%rKfXH0Uj4{?}2y{5usr@H!ec6?c1YVxU0LKnJd4l1wltjE8vbbhNVC z4Vb-b6tVysegoOVeGdVGDE$V~q}tvBbddU$V2v?1@!YH`B>>J-Gi@fid=qL3K`N$F zCUmxhD9rcL=*pCR3r95fGtrCEcMR&@!U~^ImBI2`ST+V!7hr(Yxu*CHqG7kulCT!S zkT0d&Ms|>k%dG;0wK17U|E{pBs%D`P-}I$6Sy=2-a5M=_w+ETDls5qF|A_mnarI1yG zmhsG7x`USC9MkS<@LepLnbR4h&o$xhgt+b!eHWp)H^Z53BK4W=%vfkrF}WxWy9d80 zT9K8YdhcN5yr4@G(;XL?yeT2Kuw%>Jhb&?_%Ozdc4SH2W%pt*a;5MZI zbDu%t`hmfRXK2BzJOMgLiTO-!dJgqQMQHL{jQFh2=)swi8T%J65b8OuOb6<~oOLso z=9MW=YgP~N#~MW|j1^p7!nu5%V$(oByhLZ6_O~S+F$mo==CeHml;+_xKUPlvpY3^4dZ>P+gXZz zjlQ7Ttn#zjjUK*6z#Bw-B@Q(Q8~z6KvlmcHKt=vD^~jGVY%(g{kg>8M91bG_>&} zT0(17%%_jAvwb5~$;0dH&O{;crJN+>wVU%$`u-MXVrW*-jcfKPC? zS~Am1KVe8u`iH@%PiS4qy$tH@gV7H8xGJuvD)|`wN%@%XOQkAOBYA$tJn4NL$A>AB61*Y`GO7_ zbd|w|Yi4h<6`)kh>&!&o05eW7rEW6QE7R;nDPLeGrvP?F+!A!zxC(L=>0y@rZ>n&| ztci<}@on8*7T$&M-hCF1|mCbv1HxX=*5gO&Ynr)S&_ci&m~9Rj8x@eCMV`u-;cz7(Io5YjLL% zM!bAH(V{6b_AW)8#@g`kJ01MWudZSi3g&E0h4G|A1{BS!XK|VdvAHRXl&x>^WZV7q zu-)+oL6@ZX1{O2be1aaI*4nAu@5tYULV+H&)M?A$&vw|?u{-#?0Y*fwZa`1>Mk+4q zSkaBeq0+zInHgx5!==og4CLMx?6MotcYS{*53}5uPW7=kp8XLf*c<-~)0a(hE$MSV z0ivW*zcQI=mTODdg9T_vJuT=HA7suJd61MpTKtxyU@J5xj1?NeG)sV9e=>M##VClG zAVz^NRi0#VqtlTVAL`)&U-BXqI*3z(|L`&*HJ_x=CW@Jij`8<|_UR})9X}1lbG#Am z8J8$SsZCt^$JCflgV^7)(etK?Kn7UHJP6tRv z9p8JSQtV_DdhSY3cVjfzt6t>|W6^t5vTNQ5TtbSY{632xZ_oYY1I7FM6xu?esTN#S z7Z;%S3R&e;l`P*!{$A>RKw-=@qP{qu5wCV*ibDJFQAMVqFUKr;+Ful2{&3Px< zy}6_SH>!BWV&ZT#@`G~|42=$_nk8v8eH zsI&qz;lv7?=!Q%c{n~~(VD@c=u~9b}Iz6+QSt-juNR{s@z?00y<^PlP_nE2pz*2(7 z7Ds^x4;03WGK$OJNrxUW10UV!Qw|cC zjZt%iZfB`r9+#;Vi_qIQx2i303Uu&%np{@yDxLaE{DzXY9H#ALVvxVcY878q;7xpq zQ>l{)tYBS=wtoFiZNPFTtxibAgw2)9t)A2>6oICdf+C{ step - moveToEndPosition = new MoveStackerToFloor(); + //moveToEndPosition = new MoveStackerToFloor(); } protected void end () @@ -31,6 +31,6 @@ protected void end () * This is in end because we don't want this to execute if the sequence * was cancelled (and interrupted was called instead of end) */ - moveToEndPosition.start(); + //moveToEndPosition.start(); } } diff --git a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java index df1eb86..0500d8a 100644 --- a/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java +++ b/src/org/usfirst/frc/team3316/robot/stacker/commands/MoveStacker.java @@ -23,7 +23,7 @@ public abstract class MoveStacker extends Command public MoveStacker() { requires(Robot.stacker); - setpoint = setSetpointState(); + setpoint = this.setSetpointState(); } protected void initialize() {} @@ -38,6 +38,7 @@ protected void execute() protected boolean isFinished() { + if (Robot.stacker.getPosition() == setpoint) { return true; @@ -62,6 +63,7 @@ private void set () { setSuccessful = true; } + Robot.stacker.setSetpointState(setpoint); } protected abstract StackerPosition setSetpointState(); diff --git a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java index 4b463d3..5a7e2e9 100644 --- a/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java +++ b/src/org/usfirst/frc/team3316/robot/subsystems/Stacker.java @@ -22,7 +22,6 @@ public class Stacker extends Subsystem { private class StackerManager extends TimerTask { - private StackerPosition currentState; private StackerPosition setpointState; @@ -67,6 +66,7 @@ else if (currentState == StackerPosition.Floor) if (!Robot.stacker.getSwitchRatchetLeft() || !Robot.stacker.getSwitchRatchetRight()) { + setpointState = null; return null; } @@ -99,6 +99,7 @@ else if (currentState == StackerPosition.Floor) if (!Robot.stacker.getSwitchRatchetLeft() || !Robot.stacker.getSwitchRatchetRight()) { + setpointState = null; return null; } @@ -146,6 +147,7 @@ else if (currentState == StackerPosition.Step) return setpointState; } + public void run () { currentState = Robot.stacker.getPosition(); @@ -272,9 +274,19 @@ public boolean closeSolenoidGripper () return true; } + double[] prevHeights = new double[100]; + public double getHeight () { - return (1 / heightIR.getVoltage()); + double currentHeight = (1 / heightIR.getVoltage()); + double avg = currentHeight; + for(int i=0; i