diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/ProtoAutoClose_V3.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/ProtoAutoClose_V3.java index a03f24d..8effe66 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/ProtoAutoClose_V3.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/ProtoAutoClose_V3.java @@ -76,7 +76,7 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive; -import org.firstinspires.ftc.teamcode.utils.FlywheelV2; +import org.firstinspires.ftc.teamcode.utils.Flywheel; import org.firstinspires.ftc.teamcode.utils.Robot; import org.firstinspires.ftc.teamcode.utils.Servos; @@ -93,7 +93,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode { Robot robot; MultipleTelemetry TELE; MecanumDrive drive; - FlywheelV2 flywheel; + Flywheel flywheel; Servos servo; double velo = 0.0; boolean gpp = false; @@ -109,10 +109,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode { public Action initShooter(int vel) { return new Action() { public boolean run(@NonNull TelemetryPacket telemetryPacket) { - powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()); - velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()); - robot.shooter1.setPower(powPID); - robot.shooter2.setPower(powPID); + flywheel.manageFlywheel(vel); + velo = flywheel.getVelo(); TELE.addData("Velocity", velo); TELE.update(); @@ -180,10 +178,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode { @Override public boolean run(@NonNull TelemetryPacket telemetryPacket) { - powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()); - velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()); - robot.shooter1.setPower(powPID); - robot.shooter2.setPower(powPID); + flywheel.manageFlywheel(vel); + velo = flywheel.getVelo(); spinPID = servo.setSpinPos(spindexer); robot.spin1.setPower(spinPID); @@ -224,10 +220,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode { TELE.addLine("shooting"); TELE.update(); - powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()); - velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()); - robot.shooter1.setPower(powPID); - robot.shooter2.setPower(powPID); + flywheel.manageFlywheel(vel); + velo = flywheel.getVelo(); drive.updatePoseEstimate(); @@ -376,10 +370,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode { } ticker++; - powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()); - velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()); - robot.shooter1.setPower(powPID); - robot.shooter2.setPower(powPID); + flywheel.manageFlywheel(vel); + velo = flywheel.getVelo(); double s1D = robot.color1.getDistance(DistanceUnit.MM); double s2D = robot.color2.getDistance(DistanceUnit.MM); @@ -454,7 +446,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode { robot = new Robot(hardwareMap); - flywheel = new FlywheelV2(); + flywheel = new Flywheel(hardwareMap); TELE = new MultipleTelemetry( telemetry, FtcDashboard.getInstance().getTelemetry() diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/ServoPositions.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/ServoPositions.java index da99606..b0a886f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/ServoPositions.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/ServoPositions.java @@ -7,9 +7,9 @@ public class ServoPositions { public static double spindexer_intakePos1 = 0.39; - public static double spindexer_intakePos2 = 0.5; + public static double spindexer_intakePos2 = 0.55;//0.5; - public static double spindexer_intakePos3 = 0.66; + public static double spindexer_intakePos3 = 0.71;//0.66; public static double spindexer_outtakeBall3 = 0.47; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/TeleopV2.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/TeleopV2.java index bb1ef9d..4212355 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/TeleopV2.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/TeleopV2.java @@ -129,7 +129,7 @@ public class TeleopV2 extends LinearOpMode { telemetry, FtcDashboard.getInstance().getTelemetry() ); servo = new Servos(hardwareMap); - flywheel = new Flywheel(); + flywheel = new Flywheel(hardwareMap); drive = new MecanumDrive(hardwareMap, teleStart); @@ -282,12 +282,9 @@ public class TeleopV2 extends LinearOpMode { //SHOOTER: - double powPID = flywheel.manageFlywheel((int) vel, robot.shooter1.getCurrentPosition()); + double powPID = flywheel.manageFlywheel((int) vel); - robot.shooter1.setPower(powPID); - robot.shooter2.setPower(powPID); - - robot.transfer.setPower(1); + robot.transfer.setPower(1); //TURRET: diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/TeleopV3.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/TeleopV3.java index e003d7b..229d051 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/TeleopV3.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/TeleopV3.java @@ -29,9 +29,10 @@ import com.qualcomm.robotcore.hardware.DcMotor; import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive; -import org.firstinspires.ftc.teamcode.utils.FlywheelV2; +import org.firstinspires.ftc.teamcode.utils.Flywheel; import org.firstinspires.ftc.teamcode.utils.Robot; import org.firstinspires.ftc.teamcode.utils.Servos; +import org.firstinspires.ftc.teamcode.utils.Spindexer; import java.util.ArrayList; import java.util.List; @@ -70,8 +71,9 @@ public class TeleopV3 extends LinearOpMode { Robot robot; MultipleTelemetry TELE; Servos servo; - FlywheelV2 flywheel; + Flywheel flywheel; MecanumDrive drive; + Spindexer spindexer; double autoHoodOffset = 0.0; int shooterTicker = 0; @@ -96,7 +98,8 @@ public class TeleopV3 extends LinearOpMode { boolean shootA = true; boolean shootB = true; boolean shootC = true; - boolean autoSpintake = true; + boolean autoSpintake = false; + boolean enableSpindexerManager = true; List shootOrder = new ArrayList<>(); boolean outtake1 = false; boolean outtake2 = false; @@ -142,8 +145,9 @@ public class TeleopV3 extends LinearOpMode { robot = new Robot(hardwareMap); TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry()); servo = new Servos(hardwareMap); - flywheel = new FlywheelV2(); + flywheel = new Flywheel(hardwareMap); drive = new MecanumDrive(hardwareMap, teleStart); + spindexer = new Spindexer(hardwareMap); PIDFController tController = new PIDFController(tp, ti, td, tf); @@ -402,10 +406,7 @@ public class TeleopV3 extends LinearOpMode { //SHOOTER: - double powPID = flywheel.manageFlywheel((int) vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()); - - robot.shooter1.setPower(powPID); - robot.shooter2.setPower(powPID); + flywheel.manageFlywheel(vel); //VELOCITY AUTOMATIC @@ -588,7 +589,7 @@ public class TeleopV3 extends LinearOpMode { // } // } - if (gamepad1.left_bumper) { + if (gamepad1.left_bumper && !enableSpindexerManager) { robot.transferServo.setPosition(transferServo_out); @@ -619,14 +620,14 @@ public class TeleopV3 extends LinearOpMode { } - if (gamepad1.leftBumperWasReleased()) { + if (gamepad1.leftBumperWasReleased() && !enableSpindexerManager) { shootStamp = getRuntime(); shootAll = true; shooterTicker = 0; } - if (shootAll) { + if (shootAll && !enableSpindexerManager) { TELE.addData("100% works", shootOrder); @@ -658,6 +659,63 @@ public class TeleopV3 extends LinearOpMode { } } + + if (enableSpindexerManager) { + if (!shootAll) { + spindexer.processIntake(); + } + + // RIGHT_BUMPER + if (gamepad1.right_bumper) { + robot.intake.setPower(1); + + } else { + robot.intake.setPower(0); + } + + // LEFT_BUMPER + if (!shootAll && + (gamepad1.leftBumperWasReleased() || + gamepad1.leftBumperWasPressed() || + gamepad1.left_bumper)) { + shootStamp = getRuntime(); + shootAll = true; + + shooterTicker = 0; + } + + if (shootAll) { + + intake = false; + reject = false; + + shooterTicker++; + + // TODO: Change starting position based on desired order to shoot green ball + spindexPos = spindexer_intakePos1; + + if (getRuntime() - shootStamp < 3.5) { + + robot.transferServo.setPosition(transferServo_in); + + robot.spin1.setPower(-spinPow); + robot.spin2.setPower(spinPow); + + } else { + robot.transferServo.setPosition(transferServo_out); + //spindexPos = spindexer_intakePos1; + + shootAll = false; + + robot.transferServo.setPosition(transferServo_out); + + spindexer.resetSpindexer(); + spindexer.processIntake(); + } + } + } + + // // if (shootAll) { // @@ -824,7 +882,6 @@ public class TeleopV3 extends LinearOpMode { // } //EXTRA STUFFINESS: - drive.updatePoseEstimate(); for (LynxModule hub : allHubs) { @@ -840,15 +897,20 @@ public class TeleopV3 extends LinearOpMode { TELE.addData("distanceToGoal", distanceToGoal); TELE.addData("hood", robot.hood.getPosition()); TELE.addData("targetVel", vel); - TELE.addData("Velocity", flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition())); - + TELE.addData("Velocity", flywheel.getVelo()); TELE.addData("shootOrder", shootOrder); TELE.addData("oddColor", oddBallColor); TELE.addData("spinEqual", servo.spinEqual(spindexer_intakePos1)); + TELE.addData("spinCommmandedPos", spindexer.commandedIntakePosition); + TELE.addData("spinIntakeState", spindexer.currentIntakeState); + TELE.addData("spinTestCounter", spindexer.counter); TELE.addData("autoSpintake", autoSpintake); + TELE.addData("distanceRearCenter", spindexer.distanceRearCenter); + TELE.addData("distanceFrontDriver", spindexer.distanceFrontDriver); + TELE.addData("distanceFrontPassenger", spindexer.distanceFrontPassenger); + TELE.addData("shootall commanded", shootAll); TELE.addData("timeSinceStamp", getRuntime() - shootStamp); - TELE.update(); ticker++; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/ShooterTest.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/ShooterTest.java index 04600ae..4e036fa 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/ShooterTest.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/ShooterTest.java @@ -9,7 +9,7 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.hardware.DcMotorEx; -import org.firstinspires.ftc.teamcode.utils.FlywheelV2; +import org.firstinspires.ftc.teamcode.utils.Flywheel; import org.firstinspires.ftc.teamcode.utils.Robot; @Config @@ -21,12 +21,17 @@ public class ShooterTest extends LinearOpMode { // --- CONSTANTS YOU TUNE --- //TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED + public static double Velocity = 0.0; + public static double P = 40.0; + public static double I = 0.3; + public static double D = 7.0; + public static double F = 10.0; public static double transferPower = 1.0; public static double hoodPos = 0.501; public static double turretPos = 0.501; public static boolean shoot = false; Robot robot; - FlywheelV2 flywheel; + Flywheel flywheel; @Override public void runOpMode() throws InterruptedException { @@ -34,7 +39,7 @@ public class ShooterTest extends LinearOpMode { robot = new Robot(hardwareMap); DcMotorEx leftShooter = robot.shooter1; DcMotorEx rightShooter = robot.shooter2; - flywheel = new FlywheelV2(); + flywheel = new Flywheel(hardwareMap); MultipleTelemetry TELE = new MultipleTelemetry( telemetry, FtcDashboard.getInstance().getTelemetry() @@ -50,10 +55,8 @@ public class ShooterTest extends LinearOpMode { rightShooter.setPower(parameter); leftShooter.setPower(parameter); } else if (mode == 1) { - double powPID = flywheel.manageFlywheel((int) parameter, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()); - rightShooter.setPower(powPID); - leftShooter.setPower(powPID); - TELE.addData("PIDPower", powPID); + flywheel.setPIDF(P,I,D,F); + flywheel.manageFlywheel((int) Velocity); } if (hoodPos != 0.501) { @@ -67,7 +70,7 @@ public class ShooterTest extends LinearOpMode { } else { robot.transferServo.setPosition(transferServo_out); } - TELE.addData("Velocity", flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition())); + TELE.addData("Velocity", flywheel.getVelo()); TELE.addData("Velocity 1", flywheel.getVelo1()); TELE.addData("Velocity 2", flywheel.getVelo2()); TELE.addData("Power", robot.shooter1.getPower()); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Flywheel.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Flywheel.java index 6f67a59..495b9db 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Flywheel.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Flywheel.java @@ -2,6 +2,9 @@ package org.firstinspires.ftc.teamcode.utils; import static org.firstinspires.ftc.teamcode.constants.ShooterVars.kP; import static org.firstinspires.ftc.teamcode.constants.ShooterVars.maxStep; +import com.arcrobotics.ftclib.controller.PIDFController; +import com.qualcomm.robotcore.hardware.DcMotor; +import com.qualcomm.robotcore.hardware.HardwareMap; import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; @@ -17,72 +20,65 @@ public class Flywheel { double velo = 0.0; double velo1 = 0.0; double velo2 = 0.0; - double velo3 = 0.0; - double velo4 = 0.0; - double velo5 = 0.0; double targetVelocity = 0.0; double powPID = 0.0; boolean steady = false; - public Flywheel () { - //robot = new Robot(hardwareMap); + public Flywheel (HardwareMap hardwareMap) { + robot = new Robot(hardwareMap); } public double getVelo () { return velo; } + public double getVelo1 () { + return velo1; + } + public double getVelo2 () { + return velo2; + } public boolean getSteady() { return steady; } + // Set the robot PIDF for the next cycle. + public void setPIDF(double p, double i, double d, double f) { + robot.shooterPIDF.p = p; + robot.shooterPIDF.i = i; + robot.shooterPIDF.d = d; + robot.shooterPIDF.f = f; + } private double getTimeSeconds () { return (double) System.currentTimeMillis()/1000.0; } + // Convert from RPM to Ticks per Second + private double RPM_to_TPS (double RPM) { return (RPM*28.0)/60.0;} - public double manageFlywheel(int commandedVelocity, double shooter1CurPos) { + // Convert from Ticks per Second to RPM + private double TPS_to_RPM (double TPS) { return (TPS*60.0)/28.0;} + + public double manageFlywheel(double commandedVelocity) { targetVelocity = commandedVelocity; - ticker++; - if (ticker % 2 == 0) { - velo5 = velo4; - velo4 = velo3; - velo3 = velo2; - velo2 = velo1; + // Turn PIDF for Target Velocities + //robot.shooterPIDF.p = P; + //robot.shooterPIDF.i = I; + //robot.shooterPIDF.d = D; + //robot.shooterPIDF.f = F; + robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, robot.shooterPIDF); + robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, robot.shooterPIDF); + robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity)); + robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity)); - currentPos = shooter1CurPos / 2048; - stamp = getTimeSeconds(); //getRuntime(); - velo1 = -60 * ((currentPos - initPos) / (stamp - stamp1)); - initPos = currentPos; - stamp1 = stamp; - - velo = (velo1 + velo2 + velo3 + velo4 + velo5) / 5; - } - // Flywheel control code here - if (targetVelocity - velo > 500) { - powPID = 1.0; - } else if (velo - targetVelocity > 500){ - powPID = 0.0; - } else { - double feed = Math.log((668.39 / (targetVelocity + 591.96)) - 0.116) / -4.18; - - // --- PROPORTIONAL CORRECTION --- - double error = targetVelocity - velo; - double correction = kP * error; - - // limit how fast power changes (prevents oscillation) - correction = Math.max(-maxStep, Math.min(maxStep, correction)); - - // --- FINAL MOTOR POWER --- - powPID = feed + correction; - - // clamp to allowed range - powPID = Math.max(0, Math.min(1, powPID)); - } + // Record Current Velocity + velo1 = TPS_to_RPM(robot.shooter1.getVelocity()); + velo2 = TPS_to_RPM(robot.shooter1.getVelocity()); // Possible error: should it be shooter2 not shooter1? + velo = Math.max(velo1,velo2); // really should be a running average of the last 5 - steady = (Math.abs(targetVelocity - velo) < 100.0); + steady = (Math.abs(targetVelocity - velo) < 200.0); return powPID; } @@ -90,4 +86,4 @@ public class Flywheel { public void update() { } -} \ No newline at end of file +} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Robot.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Robot.java index 1e1d096..6ff9e6f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Robot.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Robot.java @@ -8,6 +8,7 @@ import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx; import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.HardwareMap; +import com.qualcomm.robotcore.hardware.PIDFCoefficients; import com.qualcomm.robotcore.hardware.Servo; import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName; @@ -23,6 +24,13 @@ public class Robot { public DcMotorEx backRight; public DcMotorEx intake; public DcMotorEx transfer; + public PIDFCoefficients shooterPIDF; + public double shooterPIDF_P = 10.0; + public double shooterPIDF_I = 0.6; + public double shooterPIDF_D = 5.0; + public double shooterPIDF_F = 10.0; + + public double[] shooterPIDF_StepSizes = {10.0,1.0,0.001, 0.0001}; public DcMotorEx shooter1; public DcMotorEx shooter2; public Servo hood; @@ -69,8 +77,11 @@ public class Robot { shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2"); //TODO: figure out which shooter motor is reversed using ShooterTest and change it in code @KeshavAnandCode shooter1.setDirection(DcMotorSimple.Direction.REVERSE); - shooter1.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER); - shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER); + shooterPIDF = new PIDFCoefficients(shooterPIDF_P,shooterPIDF_I , shooterPIDF_D, shooterPIDF_F); + shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER); + shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF); + shooter2.setMode(DcMotor.RunMode.RUN_USING_ENCODER); + shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF); hood = hardwareMap.get(Servo.class, "hood"); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java new file mode 100644 index 0000000..e5b7d5b --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java @@ -0,0 +1,400 @@ +package org.firstinspires.ftc.teamcode.utils; + +import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; +import com.arcrobotics.ftclib.controller.PIDFController; +import com.qualcomm.robotcore.hardware.HardwareMap; + +import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1; +import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos2; +import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos3; +import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1; +import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2; +import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3; +import static org.firstinspires.ftc.teamcode.utils.Servos.spinD; +import static org.firstinspires.ftc.teamcode.utils.Servos.spinF; +import static org.firstinspires.ftc.teamcode.utils.Servos.spinI; +import static org.firstinspires.ftc.teamcode.utils.Servos.spinP; + +import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; +import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive; + +public class Spindexer { + Robot robot; + Servos servos; + Flywheel flywheel; + MecanumDrive drive; + double lastKnownSpinPos = 0.0; + MultipleTelemetry TELE; + + PIDFController spinPID = new PIDFController(spinP, spinI, spinD, spinF); + + double spinCurrentPos = 0.0; + + public int commandedIntakePosition = 0; + + public double distanceRearCenter = 0.0; + public double distanceFrontDriver = 0.0; + public double distanceFrontPassenger = 0.0; + + // For Use + enum RotatedBallPositionNames { + REARCENTER, + FRONTDRIVER, + FRONTPASSENGER + } + // Array of commandedIntakePositions with contents + // {RearCenter, FrontDriver, FrontPassenger} + static final int[][] RotatedBallPositions = {{0,2,1}, {1,0,2}, {2,1,0}}; + class spindexerBallRoatation { + int rearCenter = 0; // aka commanded Position + int frontDriver = 0; + int frontPassenger = 0; + } + + enum IntakeState { + UNKNOWN, + INTAKE, + FINDNEXT, + MOVING, + FULL, + SHOOTNEXT, + SHOOTMOVING, + SHOOTWAIT, + }; + + public IntakeState currentIntakeState = IntakeState.UNKNOWN; + + enum BallColor { + UNKNOWN, + GREEN, + PURPLE + }; + + class BallPosition { + boolean isEmpty = true; + int foundEmpty = 0; + BallColor ballColor = BallColor.UNKNOWN; + } + + BallPosition[] ballPositions = new BallPosition[3]; + + public boolean init () { + return true; + } + + public Spindexer(HardwareMap hardwareMap) { + robot = new Robot(hardwareMap); + servos = new Servos(hardwareMap); + flywheel = new Flywheel(hardwareMap); + //TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry()); + + lastKnownSpinPos = servos.getSpinPos(); + + ballPositions[0] = new BallPosition(); + ballPositions[1] = new BallPosition(); + ballPositions[2] = new BallPosition(); + + + } + + + double[] outakePositions = + {spindexer_outtakeBall1, spindexer_outtakeBall2, spindexer_outtakeBall3}; + + double[] intakePositions = + {spindexer_intakePos1, spindexer_intakePos2, spindexer_intakePos3}; + + public int counter = 0; + +// private double getTimeSeconds () +// { +// return (double) System.currentTimeMillis()/1000.0; +// } + +// public double getPos() { +// robot.spin1Pos.getVoltage(); +// robot.spin1Pos.getMaxVoltage(); +// return (robot.spin1Pos.getVoltage()/robot.spin1Pos.getMaxVoltage()); +// } + +// public void manageSpindexer() { +// +// } + + public void resetBallPosition (int pos) { + ballPositions[pos].isEmpty = true; + ballPositions[pos].foundEmpty = 0; + ballPositions[pos].ballColor = BallColor.UNKNOWN; + } + + public void resetSpindexer () { + for (int i = 0; i < 3; i++) { + resetBallPosition(i); + } + currentIntakeState = IntakeState.UNKNOWN; + } + + // Detects if a ball is found and what color. + // Returns true is there was a new ball found in Position 1 + // FIXIT: Reduce number of times that we read the color sensors for loop times. + public boolean detectBalls() { + + boolean newPos1Detection = false; + int spindexerBallPos = 0; + + // Read Distances + distanceRearCenter = robot.color1.getDistance(DistanceUnit.MM); + distanceFrontDriver = robot.color2.getDistance(DistanceUnit.MM); + distanceFrontPassenger = robot.color3.getDistance(DistanceUnit.MM); + + // Position 1 + if (distanceRearCenter < 43) { + + // Mark Ball Found + newPos1Detection = true; + + // Detect which color + double green = robot.color1.getNormalizedColors().green; + double red = robot.color1.getNormalizedColors().red; + double blue = robot.color1.getNormalizedColors().blue; + + double gP = green / (green + red + blue); + + // FIXIT - Add filtering to improve accuracy. + if (gP >= 0.4) { + ballPositions[commandedIntakePosition].ballColor = BallColor.PURPLE; // purple + } else { + ballPositions[commandedIntakePosition].ballColor = BallColor.GREEN; // purple + } + } + // Position 2 + // Find which ball position this is in the spindexer + spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()]; + if (distanceFrontDriver < 60) { + // reset FoundEmpty because looking for 3 in a row before reset + ballPositions[spindexerBallPos].foundEmpty = 0; + // FIXIT: Comment out for now due to loop time concerns +// double green = robot.color2.getNormalizedColors().green; +// double red = robot.color2.getNormalizedColors().red; +// double blue = robot.color2.getNormalizedColors().blue; +// +// double gP = green / (green + red + blue); + +// if (gP >= 0.4) { +// b2 = 2; // purple +// } else { +// b2 = 1; // green +// } + } else { + if (!ballPositions[spindexerBallPos].isEmpty) { + if (ballPositions[spindexerBallPos].foundEmpty > 3) { + resetBallPosition(spindexerBallPos); + } + ballPositions[spindexerBallPos].foundEmpty++; + } + + } + + // Position 3 + spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTPASSENGER.ordinal()]; + if (distanceFrontPassenger < 33) { + + // reset FoundEmpty because looking for 3 in a row before reset + ballPositions[spindexerBallPos].foundEmpty = 0; + // FIXIT: Comment out for now due to loop time concerns +// double green = robot.color3.getNormalizedColors().green; +// double red = robot.color3.getNormalizedColors().red; +// double blue = robot.color3.getNormalizedColors().blue; + +// double gP = green / (green + red + blue); + +// if (gP >= 0.4) { +// b3 = 2; // purple +// } else { +// b3 = 1; // green +// } + } else { + if (!ballPositions[spindexerBallPos].isEmpty) { + if (ballPositions[spindexerBallPos].foundEmpty > 3) { + resetBallPosition(spindexerBallPos); + } + ballPositions[spindexerBallPos].foundEmpty++; + } + } + +// TELE.addData("Velocity", velo); +// TELE.addLine("Detecting"); +// TELE.addData("Distance 1", s1D); +// TELE.addData("Distance 2", s2D); +// TELE.addData("Distance 3", s3D); +// TELE.addData("B1", b1); +// TELE.addData("B2", b2); +// TELE.addData("B3", b3); +// TELE.update(); + + return newPos1Detection; + } + + public void moveSpindexerToPos(double pos) { + spinCurrentPos = servos.getSpinPos(); + + double spindexPID = spinPID.calculate(spinCurrentPos, pos); + + robot.spin1.setPower(spindexPID); + robot.spin2.setPower(-spindexPID); + } + + public void stopSpindexer() { + robot.spin1.setPower(0); + robot.spin2.setPower(0); + } + + public boolean isFull () { + return (!ballPositions[0].isEmpty && !ballPositions[1].isEmpty && !ballPositions[2].isEmpty); + } + public boolean processIntake() { + + switch (currentIntakeState) { + case UNKNOWN: + // For now just set position ONE if UNKNOWN + commandedIntakePosition = 0; + servos.setSpinPos(intakePositions[0]); + currentIntakeState = Spindexer.IntakeState.MOVING; + break; + case INTAKE: + // Ready for intake and Detecting a New Ball + if (detectBalls()) { + ballPositions[commandedIntakePosition].isEmpty = false; + currentIntakeState = Spindexer.IntakeState.FINDNEXT; + } else { + // Maintain Position + moveSpindexerToPos(intakePositions[commandedIntakePosition]); + } + break; + case FINDNEXT: + // Find Next Open Position and start movement + double currentSpindexerPos = servos.getSpinPos(); + double commandedtravelDistance = 2.0; + double proposedTravelDistance = Math.abs(intakePositions[0] - currentSpindexerPos); + if (ballPositions[0].isEmpty && (proposedTravelDistance < commandedtravelDistance)) { + // Position 1 + commandedIntakePosition = 0; + servos.setSpinPos(intakePositions[commandedIntakePosition]); + currentIntakeState = Spindexer.IntakeState.MOVING; + commandedtravelDistance = proposedTravelDistance; + } + proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos); + if (ballPositions[1].isEmpty && (proposedTravelDistance < commandedtravelDistance)) { + // Position 2 + commandedIntakePosition = 1; + servos.setSpinPos(intakePositions[commandedIntakePosition]); + currentIntakeState = Spindexer.IntakeState.MOVING; + commandedtravelDistance = proposedTravelDistance; + } + proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos); + if (ballPositions[2].isEmpty && (proposedTravelDistance < commandedtravelDistance)) { + // Position 3 + commandedIntakePosition = 2; + servos.setSpinPos(intakePositions[commandedIntakePosition]); + currentIntakeState = Spindexer.IntakeState.MOVING; + commandedtravelDistance = proposedTravelDistance; + } + if (currentIntakeState != Spindexer.IntakeState.MOVING) { + // Full + currentIntakeState = Spindexer.IntakeState.FULL; + } + moveSpindexerToPos(intakePositions[commandedIntakePosition]); + break; + + case MOVING: + // Stopping when we get to the new position + if (servos.spinEqual(intakePositions[commandedIntakePosition])) { + currentIntakeState = Spindexer.IntakeState.INTAKE; + stopSpindexer(); + detectBalls(); + } else { + // Keep moving the spindexer + moveSpindexerToPos(intakePositions[commandedIntakePosition]); + } + break; + + case FULL: + // Double Check Colors + detectBalls(); + if (ballPositions[0].isEmpty || ballPositions[1].isEmpty || ballPositions[2].isEmpty) { + // Error handling found an empty spot, get it ready for a ball + currentIntakeState = Spindexer.IntakeState.FINDNEXT; + } + // Maintain Position + moveSpindexerToPos(intakePositions[commandedIntakePosition]); + break; + + case SHOOTNEXT: + // Find Next Open Position and start movement + if (!ballPositions[0].isEmpty) { + // Position 1 + commandedIntakePosition = 0; + servos.setSpinPos(outakePositions[commandedIntakePosition]); + currentIntakeState = Spindexer.IntakeState.SHOOTMOVING; + } else if (ballPositions[1].isEmpty) { // Possible error: should it be !ballPosition[1].isEmpty? + // Position 2 + commandedIntakePosition = 1; + servos.setSpinPos(outakePositions[commandedIntakePosition]); + currentIntakeState = Spindexer.IntakeState.SHOOTMOVING; + } else if (ballPositions[2].isEmpty) { // Possible error: should it be !ballPosition[2].isEmpty? + // Position 3 + commandedIntakePosition = 2; + servos.setSpinPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions" + currentIntakeState = Spindexer.IntakeState.SHOOTMOVING; + } else { + // Empty return to intake state + currentIntakeState = IntakeState.FINDNEXT; + } + moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions" + break; + + case SHOOTMOVING: + // Stopping when we get to the new position + if (servos.spinEqual(outakePositions[commandedIntakePosition])) { + currentIntakeState = Spindexer.IntakeState.SHOOTWAIT; + ballPositions[commandedIntakePosition].isEmpty = true; + // Advance to next full position and wait +// commandedIntakePosition++; +// if (commandedIntakePosition > 2) { +// commandedIntakePosition = 0; +// } +// // Continue moving to next position +// servos.setSpinPos(intakePositions[commandedIntakePosition]); +// currentIntakeState = Spindexer.IntakeState.MOVING; + + } else { + // Keep moving the spindexer + moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions" + } + break; + + case SHOOTWAIT: + // Stopping when we get to the new position + if (servos.spinEqual(intakePositions[commandedIntakePosition])) { + currentIntakeState = Spindexer.IntakeState.INTAKE; + stopSpindexer(); + detectBalls(); + } else { + // Keep moving the spindexer + moveSpindexerToPos(intakePositions[commandedIntakePosition]); + } + break; + + default: + // Statements to execute if no case matches + } + //TELE.addData("commandedIntakePosition", commandedIntakePosition); + //TELE.update(); + // Signal a successful intake + return false; + } + + public void update() + { + } +}