From dea9a10b087fb461f8b1052a250e6ce45538ef6b Mon Sep 17 00:00:00 2001 From: DanTheMan-byte Date: Tue, 27 Jan 2026 16:36:46 -0600 Subject: [PATCH 01/10] added targeting information and unjaming code (both untested) --- .../ftc/teamcode/teleop/TeleopV3.java | 15 ++++++++--- .../ftc/teamcode/utils/Spindexer.java | 17 ++++++++++-- .../ftc/teamcode/utils/Targeting.java | 26 +++++++++---------- .../ftc/teamcode/utils/Turret.java | 3 --- 4 files changed, 39 insertions(+), 22 deletions(-) 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 d4d3aac..c203c7a 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 @@ -3,6 +3,7 @@ package org.firstinspires.ftc.teamcode.teleop; import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1; +import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out; import static org.firstinspires.ftc.teamcode.utils.Servos.spinD; @@ -123,6 +124,7 @@ public class TeleopV3 extends LinearOpMode { private boolean transferIn = false; boolean turretInterpolate = false; public static double spinSpeedIncrease = 0.04; + public static int resetSpinTicks = 20; public static double velPrediction(double distance) { if (distance < 30) { @@ -582,8 +584,12 @@ public class TeleopV3 extends LinearOpMode { // } if (enableSpindexerManager) { - if (!shootAll) { + // Gives some time to reset spindexer + if (!shootAll && intakeTicker > resetSpinTicks) { spindexer.processIntake(); + } else { + robot.spin1.setPosition(spindexer_intakePos1); + robot.spin2.setPosition(1-spindexer_intakePos1); } // RIGHT_BUMPER @@ -606,15 +612,16 @@ public class TeleopV3 extends LinearOpMode { spindexPos = spinStartPos;// TODO: Change starting position based on desired order to shoot green ball } - + intakeTicker++; if (shootAll) { - + intakeTicker = 0; intake = false; reject = false; - if (getRuntime() - shootStamp < 3.5) { + if (getRuntime() - shootStamp < 3.5 && servo.getSpinPos() < spindexer_outtakeBall3 + 0.1) { if (shooterTicker == 0 && !servo.spinEqual(spindexPos)){ + robot.transferServo.setPosition(transferServo_out); robot.spin1.setPosition(spindexPos); robot.spin2.setPosition(1-spindexPos); } else { 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 index 4496cae..190e00b 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java @@ -39,6 +39,8 @@ public class Spindexer { public double distanceFrontDriver = 0.0; public double distanceFrontPassenger = 0.0; + private double prevPos = 0.0; + public Types.Motif desiredMotif = Types.Motif.NONE; // For Use enum RotatedBallPositionNames { @@ -246,10 +248,21 @@ public class Spindexer { return newPos1Detection; } - - public void moveSpindexerToPos(double pos) { + // Has code to unjam spindexer + private void moveSpindexerToPos(double pos) { robot.spin1.setPosition(pos); robot.spin2.setPosition(1-pos); + double currentPos = servos.getSpinPos(); + if (!servos.spinEqual(pos) && Math.abs(prevPos - currentPos) <= 0){ + if (currentPos > pos){ + robot.spin1.setPosition(1); + robot.spin2.setPosition(0); + } else { + robot.spin1.setPosition(0); + robot.spin2.setPosition(1); + } + } + prevPos = currentPos; } public void stopSpindexer() { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Targeting.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Targeting.java index bfb87d9..12758ff 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Targeting.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Targeting.java @@ -67,19 +67,19 @@ public class Targeting { KNOWNTARGETING[3][4] = new Settings (3100.0, 0.47); KNOWNTARGETING[3][5] = new Settings (3100.0, 0.47); // ROW 4 - KNOWNTARGETING[4][0] = new Settings (4540.0, 0.1); - KNOWNTARGETING[4][1] = new Settings (4541.0, 0.1); - KNOWNTARGETING[4][2] = new Settings (4542.0, 0.1); - KNOWNTARGETING[4][3] = new Settings (4543.0, 0.1); - KNOWNTARGETING[4][4] = new Settings (4544.0, 0.1); - KNOWNTARGETING[4][5] = new Settings (4545.0, 0.1); - // ROW 1 - KNOWNTARGETING[5][0] = new Settings (4550.0, 0.1); - KNOWNTARGETING[5][1] = new Settings (4551.0, 0.1); - KNOWNTARGETING[5][2] = new Settings (4552.0, 0.1); - KNOWNTARGETING[5][3] = new Settings (4553.0, 0.1); - KNOWNTARGETING[5][4] = new Settings (4554.0, 0.1); - KNOWNTARGETING[5][5] = new Settings (4555.0, 0.1); + KNOWNTARGETING[4][0] = new Settings (3100, 0.49); + KNOWNTARGETING[4][1] = new Settings (3100, 0.49); + KNOWNTARGETING[4][2] = new Settings (3100, 0.5); + KNOWNTARGETING[4][3] = new Settings (3200, 0.5); + KNOWNTARGETING[4][4] = new Settings (3250, 0.49); + KNOWNTARGETING[4][5] = new Settings (3300, 0.49); + // ROW 5 + KNOWNTARGETING[5][0] = new Settings (3200, 0.48); + KNOWNTARGETING[5][1] = new Settings (3200, 0.48); + KNOWNTARGETING[5][2] = new Settings (3300, 0.48); + KNOWNTARGETING[5][3] = new Settings (3350, 0.48); + KNOWNTARGETING[5][4] = new Settings (3350, 0.48); + KNOWNTARGETING[5][5] = new Settings (3350, 0.48); } public Targeting() diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Turret.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Turret.java index 492a02f..d2def91 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Turret.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Turret.java @@ -119,17 +119,14 @@ public class Turret { } public double getTy() { - limelightRead(); return ty; } public double getLimelightX() { - limelightRead(); return limelightPosX; } public double getLimelightY() { - limelightRead(); return limelightPosY; } From 1715fa96cb9a141966b2f1527a5577c36ef5feab Mon Sep 17 00:00:00 2001 From: DanTheMan-byte Date: Tue, 27 Jan 2026 16:44:55 -0600 Subject: [PATCH 02/10] updated dash version --- build.dependencies.gradle | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/build.dependencies.gradle b/build.dependencies.gradle index 770fdae..28189d8 100644 --- a/build.dependencies.gradle +++ b/build.dependencies.gradle @@ -29,7 +29,7 @@ dependencies { implementation "com.acmerobotics.roadrunner:ftc:0.1.25" //RR implementation "com.acmerobotics.roadrunner:core:1.0.1" //RR implementation "com.acmerobotics.roadrunner:actions:1.0.1" //RR - implementation "com.acmerobotics.dashboard:dashboard:0.4.17" //FTC Dash + implementation "com.acmerobotics.dashboard:dashboard:0.5.1" //FTC Dash implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB From 2fd87c90936c1665f22613db6bcc9c9c710081c1 Mon Sep 17 00:00:00 2001 From: DanTheMan-byte Date: Tue, 27 Jan 2026 18:38:41 -0600 Subject: [PATCH 03/10] @Matt please take a look at this code --- .../teamcode/constants/ServoPositions.java | 4 +- .../ftc/teamcode/teleop/TeleopV3.java | 114 +++++++++--------- .../ftc/teamcode/utils/Spindexer.java | 4 + 3 files changed, 65 insertions(+), 57 deletions(-) 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 63a5661..ebf480f 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 @@ -11,11 +11,11 @@ public class ServoPositions { public static double spindexer_intakePos3 = 0.53;//0.66; - public static double spindexer_outtakeBall3 = 0.8; + public static double spindexer_outtakeBall3 = 0.24; public static double spindexer_outtakeBall2 = 0.6; public static double spindexer_outtakeBall1 = 0.4; - public static double spinStartPos = spindexer_outtakeBall1 - 0.08; + public static double spinStartPos = spindexer_outtakeBall3 - 0.1; public static double transferServo_out = 0.15; 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 c203c7a..5ce64b7 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 @@ -3,6 +3,9 @@ package org.firstinspires.ftc.teamcode.teleop; import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos; 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_outtakeBall2; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out; @@ -123,8 +126,8 @@ public class TeleopV3 extends LinearOpMode { private int tickerA = 1; private boolean transferIn = false; boolean turretInterpolate = false; - public static double spinSpeedIncrease = 0.04; - public static int resetSpinTicks = 20; + public static double spinSpeedIncrease = 0.03; + public static int resetSpinTicks = 4; public static double velPrediction(double distance) { if (distance < 30) { @@ -584,20 +587,18 @@ public class TeleopV3 extends LinearOpMode { // } if (enableSpindexerManager) { - // Gives some time to reset spindexer - if (!shootAll && intakeTicker > resetSpinTicks) { + // RIGHT_BUMPER + if (gamepad1.right_bumper && intakeTicker > resetSpinTicks) { + robot.intake.setPower(1); spindexer.processIntake(); - } else { - robot.spin1.setPosition(spindexer_intakePos1); - robot.spin2.setPosition(1-spindexer_intakePos1); - } - - // RIGHT_BUMPER - if (gamepad1.right_bumper) { - robot.intake.setPower(1); - } else { robot.intake.setPower(0); + if (spindexer.isFull() && intakeTicker > resetSpinTicks*5){ + robot.spin1.setPosition(spinStartPos); + robot.spin2.setPosition(1-spinStartPos); + } else { + spindexer.processIntake(); + } } // LEFT_BUMPER @@ -609,7 +610,6 @@ public class TeleopV3 extends LinearOpMode { shootAll = true; shooterTicker = 0; - spindexPos = spinStartPos;// TODO: Change starting position based on desired order to shoot green ball } intakeTicker++; @@ -618,18 +618,23 @@ public class TeleopV3 extends LinearOpMode { intake = false; reject = false; - if (getRuntime() - shootStamp < 3.5 && servo.getSpinPos() < spindexer_outtakeBall3 + 0.1) { + if (servo.getSpinPos() < spindexer_outtakeBall2 + 0.4 || shooterTicker == 0) { - if (shooterTicker == 0 && !servo.spinEqual(spindexPos)){ + if (shooterTicker == 0){ robot.transferServo.setPosition(transferServo_out); - robot.spin1.setPosition(spindexPos); - robot.spin2.setPosition(1-spindexPos); + robot.spin1.setPosition(spinStartPos); + robot.spin2.setPosition(1-spinStartPos); + if (servo.spinEqual(spinStartPos)){ + shooterTicker++; + } + TELE.addLine("starting to shoot"); } else { robot.transferServo.setPosition(transferServo_in); shooterTicker++; - double prevSpinPos = robot.spin1.getPosition(); + double prevSpinPos = servo.getSpinPos(); robot.spin1.setPosition(prevSpinPos + spinSpeedIncrease); robot.spin2.setPosition(1 - prevSpinPos - spinSpeedIncrease); + TELE.addLine("shooting"); } } else { @@ -640,6 +645,7 @@ public class TeleopV3 extends LinearOpMode { spindexer.resetSpindexer(); spindexer.processIntake(); + TELE.addLine("stop shooting"); } } @@ -825,42 +831,40 @@ public class TeleopV3 extends LinearOpMode { hub.clearBulkCache(); } // - TELE.addData("Spin1Green", green1 + ": " + ballIn(1)); - TELE.addData("Spin2Green", green2 + ": " + ballIn(2)); - TELE.addData("Spin3Green", green3 + ": " + ballIn(3)); - - TELE.addData("pose", drive.localizer.getPose()); - TELE.addData("heading", drive.localizer.getPose().heading.toDouble()); - TELE.addData("distanceToGoal", distanceToGoal); - TELE.addData("hood", robot.hood.getPosition()); - TELE.addData("targetVel", vel); - TELE.addData("Velocity", flywheel.getVelo()); - TELE.addData("Velo1", flywheel.velo1); - TELE.addData("Velo2", flywheel.velo2); - TELE.addData("shootOrder", shootOrder); - TELE.addData("oddColor", oddBallColor); - - // Spindexer Debug - 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); - // Targeting Debug - TELE.addData("robotX", robotX); - TELE.addData("robotY", robotY); - TELE.addData("robotInchesX", targeting.robotInchesX); - TELE.addData( "robotInchesY", targeting.robotInchesY); - TELE.addData("Targeting Interpolate", turretInterpolate); - TELE.addData("Targeting GridX", targeting.robotGridX); - TELE.addData("Targeting GridY", targeting.robotGridY); - TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM); - TELE.addData("Targeting HoodAngle", targetingSettings.hoodAngle); - TELE.addData("timeSinceStamp", getRuntime() - shootStamp); +// TELE.addData("Spin1Green", green1 + ": " + ballIn(1)); +// TELE.addData("Spin2Green", green2 + ": " + ballIn(2)); +// TELE.addData("Spin3Green", green3 + ": " + ballIn(3)); +// +// TELE.addData("pose", drive.localizer.getPose()); +// TELE.addData("heading", drive.localizer.getPose().heading.toDouble()); +// TELE.addData("distanceToGoal", distanceToGoal); +// TELE.addData("hood", robot.hood.getPosition()); +// TELE.addData("targetVel", vel); +// TELE.addData("Velocity", flywheel.getVelo()); +// TELE.addData("Velo1", flywheel.velo1); +// TELE.addData("Velo2", flywheel.velo2); +// TELE.addData("shootOrder", shootOrder); +// TELE.addData("oddColor", oddBallColor); +// +// // Spindexer Debug +// 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("shootall commanded", shootAll); +// // Targeting Debug +// TELE.addData("robotX", robotX); +// TELE.addData("robotY", robotY); +// TELE.addData("robotInchesX", targeting.robotInchesX); +// TELE.addData( "robotInchesY", targeting.robotInchesY); +// TELE.addData("Targeting Interpolate", turretInterpolate); +// TELE.addData("Targeting GridX", targeting.robotGridX); +// TELE.addData("Targeting GridY", targeting.robotGridY); +// TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM); +// TELE.addData("Targeting HoodAngle", targetingSettings.hoodAngle); +// TELE.addData("timeSinceStamp", getRuntime() - shootStamp); TELE.update(); 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 index 190e00b..03d038d 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java @@ -291,6 +291,10 @@ public class Spindexer { } } + public boolean slotIsEmpty(int slot){ + return !ballPositions[slot].isEmpty; + } + public boolean isFull () { return (!ballPositions[0].isEmpty && !ballPositions[1].isEmpty && !ballPositions[2].isEmpty); } From a6fe8c14e62c14ab1394001b401eaa0db9eace9e Mon Sep 17 00:00:00 2001 From: DanTheMan-byte Date: Tue, 27 Jan 2026 18:51:24 -0600 Subject: [PATCH 04/10] @Matt please take a look at this code --- .../firstinspires/ftc/teamcode/teleop/TeleopV3.java | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) 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 5ce64b7..ae03417 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 @@ -587,18 +587,14 @@ public class TeleopV3 extends LinearOpMode { // } if (enableSpindexerManager) { + spindexer.processIntake(); + // RIGHT_BUMPER if (gamepad1.right_bumper && intakeTicker > resetSpinTicks) { robot.intake.setPower(1); - spindexer.processIntake(); } else { robot.intake.setPower(0); - if (spindexer.isFull() && intakeTicker > resetSpinTicks*5){ - robot.spin1.setPosition(spinStartPos); - robot.spin2.setPosition(1-spinStartPos); - } else { - spindexer.processIntake(); - } + } // LEFT_BUMPER @@ -618,7 +614,7 @@ public class TeleopV3 extends LinearOpMode { intake = false; reject = false; - if (servo.getSpinPos() < spindexer_outtakeBall2 + 0.4 || shooterTicker == 0) { + if (servo.getSpinPos() < spindexer_outtakeBall2 + 0.4) { if (shooterTicker == 0){ robot.transferServo.setPosition(transferServo_out); From 2a45eee878d9a6947aa15a573ea3de91346fb95f Mon Sep 17 00:00:00 2001 From: Matt9150 Date: Wed, 28 Jan 2026 00:45:21 -0600 Subject: [PATCH 05/10] Update spindexer positions after repair. --- .../ftc/teamcode/constants/ServoPositions.java | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) 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 ebf480f..d5b302b 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 @@ -5,16 +5,16 @@ import com.acmerobotics.dashboard.config.Config; @Config public class ServoPositions { - public static double spindexer_intakePos1 = 0.13; + public static double spindexer_intakePos1 = 0.00; //0.13; - public static double spindexer_intakePos2 = 0.33;//0.5; + public static double spindexer_intakePos2 = 0.19; //0.33;//0.5; - public static double spindexer_intakePos3 = 0.53;//0.66; + public static double spindexer_intakePos3 = 0.38; //0.53;//0.66; - public static double spindexer_outtakeBall3 = 0.24; + public static double spindexer_outtakeBall3 = 0.27; //0.65; //0.24; - public static double spindexer_outtakeBall2 = 0.6; - public static double spindexer_outtakeBall1 = 0.4; + public static double spindexer_outtakeBall2 = 0.65; //0.46; //0.6; + public static double spindexer_outtakeBall1 = 0.46; //0.27; //0.4; public static double spinStartPos = spindexer_outtakeBall3 - 0.1; From d088fba20a586996e0e8e1cd9caf1400639e6b5d Mon Sep 17 00:00:00 2001 From: Matt9150 Date: Wed, 28 Jan 2026 13:06:53 -0600 Subject: [PATCH 06/10] Create shootAll state machine in spindexer and call from TeleOpV3. Experiment with averaging tiles in Targeting, which is permanently disabled at the moment. --- .../ftc/teamcode/teleop/TeleopV3.java | 48 +++--- .../ftc/teamcode/utils/Spindexer.java | 54 +++++-- .../ftc/teamcode/utils/Targeting.java | 148 ++++++++++-------- 3 files changed, 153 insertions(+), 97 deletions(-) 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 ae03417..7228585 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 @@ -614,25 +614,32 @@ public class TeleopV3 extends LinearOpMode { intake = false; reject = false; - if (servo.getSpinPos() < spindexer_outtakeBall2 + 0.4) { - - if (shooterTicker == 0){ - robot.transferServo.setPosition(transferServo_out); - robot.spin1.setPosition(spinStartPos); - robot.spin2.setPosition(1-spinStartPos); - if (servo.spinEqual(spinStartPos)){ - shooterTicker++; - } - TELE.addLine("starting to shoot"); - } else { - robot.transferServo.setPosition(transferServo_in); - shooterTicker++; - double prevSpinPos = servo.getSpinPos(); - robot.spin1.setPosition(prevSpinPos + spinSpeedIncrease); - robot.spin2.setPosition(1 - prevSpinPos - spinSpeedIncrease); - TELE.addLine("shooting"); - } - +// if (servo.getSpinPos() < spindexer_outtakeBall2 + 0.4) { +// +// if (shooterTicker == 0){ +// robot.transferServo.setPosition(transferServo_out); +// robot.spin1.setPosition(spinStartPos); +// robot.spin2.setPosition(1-spinStartPos); +// if (servo.spinEqual(spinStartPos)){ +// shooterTicker++; +// } +// TELE.addLine("starting to shoot"); +// } else { +// robot.transferServo.setPosition(transferServo_in); +// shooterTicker++; +// double prevSpinPos = servo.getSpinPos(); +// robot.spin1.setPosition(prevSpinPos + spinSpeedIncrease); +// robot.spin2.setPosition(1 - prevSpinPos - spinSpeedIncrease); +// TELE.addLine("shooting"); +// } + if (shooterTicker == 0) { + shooterTicker++; + spindexer.prepareShootAll(); + } else if (!spindexer.shootAllComplete()) { + robot.transferServo.setPosition(transferServo_in); + shooterTicker++; + spindexer.shootAll(); + TELE.addLine("starting to shoot"); } else { robot.transferServo.setPosition(transferServo_out); //spindexPos = spindexer_intakePos1; @@ -640,9 +647,10 @@ public class TeleopV3 extends LinearOpMode { shootAll = false; spindexer.resetSpindexer(); - spindexer.processIntake(); + //spindexer.processIntake(); TELE.addLine("stop shooting"); } + spindexer.processIntake(); } if (gamepad1.left_stick_button){ 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 index 03d038d..1975199 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java @@ -72,7 +72,10 @@ public class Spindexer { SHOOT_ALL_READY } + int shootWaitCount = 0; + public IntakeState currentIntakeState = IntakeState.UNKNOWN_START; + public IntakeState prevIntakeState = IntakeState.UNKNOWN_START; public int unknownColorDetect = 0; enum BallColor { UNKNOWN, @@ -397,23 +400,21 @@ public class Spindexer { case SHOOT_ALL_PREP: // We get here with function call to prepareToShootMotif // Stopping when we get to the new position - if (servos.spinEqual(intakePositions[commandedIntakePosition])) { - currentIntakeState = Spindexer.IntakeState.SHOOT_ALL_READY; - } else { + if (!servos.spinEqual(outakePositions[commandedIntakePosition])) { // Keep moving the spindexer - moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions" + moveSpindexerToPos(outakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions" } break; - case SHOOT_ALL_READY: + case SHOOT_ALL_READY: // Not used // Double Check Colors //detectBalls(false, false); // Minimize hardware calls if (ballPositions[0].isEmpty && ballPositions[1].isEmpty && ballPositions[2].isEmpty) { // All ball shot move to intake state - currentIntakeState = Spindexer.IntakeState.FINDNEXT; + currentIntakeState = Spindexer.IntakeState.SHOOTNEXT; } // Maintain Position - moveSpindexerToPos(intakePositions[commandedIntakePosition]); + moveSpindexerToPos(outakePositions[commandedIntakePosition]); break; case SHOOTNEXT: @@ -431,13 +432,13 @@ public class Spindexer { } 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" + servos.setSpinPos(outakePositions[commandedIntakePosition]); 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" + moveSpindexerToPos(outakePositions[commandedIntakePosition]); break; case SHOOTMOVING: @@ -446,15 +447,22 @@ public class Spindexer { currentIntakeState = Spindexer.IntakeState.SHOOTWAIT; } else { // Keep moving the spindexer - moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions" + moveSpindexerToPos(outakePositions[commandedIntakePosition]); } break; case SHOOTWAIT: - // Stopping when we get to the new position - if (servos.spinEqual(intakePositions[commandedIntakePosition])) { - currentIntakeState = Spindexer.IntakeState.INTAKE; - stopSpindexer(); + // Stopping when we get to the new position] + if (prevIntakeState != currentIntakeState) { + shootWaitCount = 0; + } else { + shootWaitCount++; + } + // wait 3 cycles + if ((shootWaitCount > 3) && (servos.spinEqual(intakePositions[commandedIntakePosition]))) { + currentIntakeState = Spindexer.IntakeState.SHOOTNEXT; + ballPositions[commandedIntakePosition].isEmpty = true; + //stopSpindexer(); //detectBalls(true, false); } else { // Keep moving the spindexer @@ -465,6 +473,8 @@ public class Spindexer { default: // Statements to execute if no case matches } + + prevIntakeState = currentIntakeState; //TELE.addData("commandedIntakePosition", commandedIntakePosition); //TELE.update(); // Signal a successful intake @@ -516,6 +526,22 @@ public class Spindexer { commandedIntakePosition = bestFitMotif(); } + public void prepareShootAll(){ + currentIntakeState = Spindexer.IntakeState.SHOOT_ALL_PREP; + } + public void shootAll () { + currentIntakeState = Spindexer.IntakeState.SHOOTWAIT; + } + + public boolean shootAllComplete () + { + return ((currentIntakeState != Spindexer.IntakeState.SHOOT_ALL_PREP) && + (currentIntakeState != Spindexer.IntakeState.SHOOT_ALL_READY) && + (currentIntakeState != Spindexer.IntakeState.SHOOTMOVING) && + (currentIntakeState != Spindexer.IntakeState.SHOOTNEXT) && + (currentIntakeState != Spindexer.IntakeState.SHOOTWAIT)); + } + void shootAllToIntake () { currentIntakeState = Spindexer.IntakeState.FINDNEXT; } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Targeting.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Targeting.java index 12758ff..56b70a9 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Targeting.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Targeting.java @@ -107,61 +107,81 @@ public class Targeting { // Determine if we need to interpolate based on tile position. // if near upper or lower quarter or tile interpolate with next tile. + int x0 = 0; + int y0 = 0; int x1 = 0; int y1 = 0; -// interpolate = false; -// if ((remX > TILE_UPPER_QUARTILE) && (remY > TILE_UPPER_QUARTILE) && -// (robotGridX < 5) && (robotGridY <5)) { -// // +X, +Y -// interpolate = true; -// x1 = robotGridX + 1; -// y1 = robotGridY + 1; -// } else if ((remX < TILE_LOWER_QUARTILE) && (remY < TILE_LOWER_QUARTILE) && -// (robotGridX > 0) && (robotGridY > 0)) { -// // -X, -Y -// interpolate = true; -// x1 = robotGridX - 1; -// y1 = robotGridY - 1; -// } else if ((remX > TILE_UPPER_QUARTILE) && (remY < TILE_LOWER_QUARTILE) && -// (robotGridX < 5) && (robotGridY > 0)) { -// // +X, -Y -// interpolate = true; -// x1 = robotGridX + 1; -// y1 = robotGridY - 1; -// } else if ((remX < TILE_LOWER_QUARTILE) && (remY > TILE_UPPER_QUARTILE) && -// (robotGridX > 0) && (robotGridY < 5)) { -// // -X, +Y -// interpolate = true; -// x1 = robotGridX - 1; -// y1 = robotGridY + 1; -// } else if ((remX < TILE_LOWER_QUARTILE) && (robotGridX > 0)) { -// // -X, Y -// interpolate = true; -// x1 = robotGridX - 1; -// y1 = robotGridY; -// } else if ((remY < TILE_LOWER_QUARTILE) && (robotGridY > 0)) { -// // X, -Y -// interpolate = true; -// x1 = robotGridX; -// y1 = robotGridY - 1; -// } else if ((remX > TILE_UPPER_QUARTILE) && (robotGridX < 5)) { -// // +X, Y -// interpolate = true; -// x1 = robotGridX + 1; -// y1 = robotGridY; -// } else if ((remY > TILE_UPPER_QUARTILE) && (robotGridY < 5)) { -// // X, +Y -// interpolate = true; -// x1 = robotGridX; -// y1 = robotGridY + 1; -// } + interpolate = false; + if ((remX > TILE_UPPER_QUARTILE) && (remY > TILE_UPPER_QUARTILE) && + (robotGridX < 5) && (robotGridY <5)) { + // +X, +Y + interpolate = true; + x0 = robotGridX; + x1 = robotGridX + 1; + y0 = robotGridY; + y1 = robotGridY + 1; + } else if ((remX < TILE_LOWER_QUARTILE) && (remY < TILE_LOWER_QUARTILE) && + (robotGridX > 0) && (robotGridY > 0)) { + // -X, -Y + interpolate = true; + x0 = robotGridX - 1; + x1 = robotGridX; + y0 = robotGridY - 1; + y1 = robotGridY; + } else if ((remX > TILE_UPPER_QUARTILE) && (remY < TILE_LOWER_QUARTILE) && + (robotGridX < 5) && (robotGridY > 0)) { + // +X, -Y + interpolate = true; + x0 = robotGridX; + x1 = robotGridX + 1; + y0 = robotGridY - 1; + y1 = robotGridY; + } else if ((remX < TILE_LOWER_QUARTILE) && (remY > TILE_UPPER_QUARTILE) && + (robotGridX > 0) && (robotGridY < 5)) { + // -X, +Y + interpolate = true; + x0 = robotGridX - 1; + x1 = robotGridX; + y0 = robotGridY; + y1 = robotGridY + 1; + } else if ((remX < TILE_LOWER_QUARTILE) && (robotGridX > 0)) { + // -X, Y + interpolate = true; + x0 = robotGridX - 1; + x1 = robotGridX; + y0 = robotGridY; + y1 = robotGridY; + } else if ((remY < TILE_LOWER_QUARTILE) && (robotGridY > 0)) { + // X, -Y + interpolate = true; + x0 = robotGridX; + x1 = robotGridX; + y0 = robotGridY - 1; + y1 = robotGridY; + } else if ((remX > TILE_UPPER_QUARTILE) && (robotGridX < 5)) { + // +X, Y + interpolate = true; + x0 = robotGridX; + x1 = robotGridX + 1; + y0 = robotGridY; + y1 = robotGridY; + } else if ((remY > TILE_UPPER_QUARTILE) && (robotGridY < 5)) { + // X, +Y + interpolate = true; + x0 = robotGridX; + x1 = robotGridX; + y0 = robotGridY; + y1 = robotGridY + 1; + } else { + interpolate = false; + } //clamp robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1)); robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1)); // basic search - if(!interpolate) { + if(true) { //!interpolate) { if ((robotGridY < 6) && (robotGridX <6)) { recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridX][robotGridY].flywheelRPM; recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridX][robotGridY].hoodAngle; @@ -170,27 +190,29 @@ public class Targeting { } else { // bilinear interpolation - int x0 = robotGridX; + //int x0 = robotGridX; //int x1 = Math.min(x0 + 1, KNOWNTARGETING[0].length - 1); - int y0 = robotGridY; + //int y0 = robotGridY; //int y1 = Math.min(y0 + 1, KNOWNTARGETING.length - 1); - double x = (robotInchesX - (x0 * tileSize)) / tileSize; - double y = (robotInchesY - (y0 * tileSize)) / tileSize; +// double x = (robotInchesX - (x0 * tileSize)) / tileSize; +// double y = (robotInchesY - (y0 * tileSize)) / tileSize; - double rpm00 = KNOWNTARGETING[y0][x0].flywheelRPM; - double rpm10 = KNOWNTARGETING[y0][x1].flywheelRPM; - double rpm01 = KNOWNTARGETING[y1][x0].flywheelRPM; - double rpm11 = KNOWNTARGETING[y1][x1].flywheelRPM; - - double angle00 = KNOWNTARGETING[y0][x0].hoodAngle; - double angle10 = KNOWNTARGETING[y0][x1].hoodAngle; - double angle01 = KNOWNTARGETING[y1][x0].hoodAngle; - double angle11 = KNOWNTARGETING[y1][x1].hoodAngle; - - recommendedSettings.flywheelRPM = (1 - x) * (1 - y) * rpm00 + x * (1 - y) * rpm10 + (1 - x) * y * rpm01 + x * y * rpm11; - recommendedSettings.hoodAngle = (1 - x) * (1 - y) * angle00 + x * (1 - y) * angle10 + (1 - x) * y * angle01 + x * y * angle11; +// double rpm00 = KNOWNTARGETING[y0][x0].flywheelRPM; +// double rpm10 = KNOWNTARGETING[y0][x1].flywheelRPM; +// double rpm01 = KNOWNTARGETING[y1][x0].flywheelRPM; +// double rpm11 = KNOWNTARGETING[y1][x1].flywheelRPM; +// +// double angle00 = KNOWNTARGETING[y0][x0].hoodAngle; +// double angle10 = KNOWNTARGETING[y0][x1].hoodAngle; +// double angle01 = KNOWNTARGETING[y1][x0].hoodAngle; +// double angle11 = KNOWNTARGETING[y1][x1].hoodAngle; +// recommendedSettings.flywheelRPM = (1 - x) * (1 - y) * rpm00 + x * (1 - y) * rpm10 + (1 - x) * y * rpm01 + x * y * rpm11; +// recommendedSettings.hoodAngle = (1 - x) * (1 - y) * angle00 + x * (1 - y) * angle10 + (1 - x) * y * angle01 + x * y * angle11; + // Average target tiles + recommendedSettings.flywheelRPM = (KNOWNTARGETING[x0][y0].flywheelRPM + KNOWNTARGETING[x1][y1].flywheelRPM)/2.0; + recommendedSettings.hoodAngle = (KNOWNTARGETING[x0][y0].hoodAngle + KNOWNTARGETING[x1][y1].hoodAngle)/2.0; return recommendedSettings; } } From f767e82e31ba055e40289b4a92d8db48a0d26ad5 Mon Sep 17 00:00:00 2001 From: DanTheMan-byte Date: Wed, 28 Jan 2026 13:38:04 -0600 Subject: [PATCH 07/10] changed servo positions --- .../ftc/teamcode/constants/ServoPositions.java | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) 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 d5b302b..9652da6 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 @@ -11,10 +11,10 @@ public class ServoPositions { public static double spindexer_intakePos3 = 0.38; //0.53;//0.66; - public static double spindexer_outtakeBall3 = 0.27; //0.65; //0.24; + public static double spindexer_outtakeBall3 = 0.65; //0.65; //0.24; - public static double spindexer_outtakeBall2 = 0.65; //0.46; //0.6; - public static double spindexer_outtakeBall1 = 0.46; //0.27; //0.4; + public static double spindexer_outtakeBall2 = 0.46; //0.46; //0.6; + public static double spindexer_outtakeBall1 = 0.27; //0.27; //0.4; public static double spinStartPos = spindexer_outtakeBall3 - 0.1; From 5d0a569f82b6dff98ec4444fc7644dfd12433f1f Mon Sep 17 00:00:00 2001 From: DanTheMan-byte Date: Wed, 28 Jan 2026 15:23:17 -0600 Subject: [PATCH 08/10] spindex progress: not good --- .../ftc/teamcode/teleop/TeleopV3.java | 13 +++++----- .../ftc/teamcode/utils/Spindexer.java | 26 +++++++------------ 2 files changed, 17 insertions(+), 22 deletions(-) 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 7228585..f5e77d5 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 @@ -635,11 +635,12 @@ public class TeleopV3 extends LinearOpMode { if (shooterTicker == 0) { shooterTicker++; spindexer.prepareShootAll(); + TELE.addLine("starting to shoot"); } else if (!spindexer.shootAllComplete()) { robot.transferServo.setPosition(transferServo_in); shooterTicker++; spindexer.shootAll(); - TELE.addLine("starting to shoot"); + TELE.addLine("shoot"); } else { robot.transferServo.setPosition(transferServo_out); //spindexPos = spindexer_intakePos1; @@ -851,11 +852,11 @@ public class TeleopV3 extends LinearOpMode { // TELE.addData("oddColor", oddBallColor); // // // Spindexer Debug -// 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("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("shootall commanded", shootAll); // // Targeting Debug 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 index 1975199..c167a43 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java @@ -258,11 +258,11 @@ public class Spindexer { double currentPos = servos.getSpinPos(); if (!servos.spinEqual(pos) && Math.abs(prevPos - currentPos) <= 0){ if (currentPos > pos){ - robot.spin1.setPosition(1); - robot.spin2.setPosition(0); + robot.spin1.setPosition(servos.getSpinPos() + 0.05); + robot.spin2.setPosition(1 - servos.getSpinPos() - 0.05); } else { - robot.spin1.setPosition(0); - robot.spin2.setPosition(1); + robot.spin1.setPosition(servos.getSpinPos() - 0.05); + robot.spin2.setPosition(1 - servos.getSpinPos() + 0.05); } } prevPos = currentPos; @@ -307,7 +307,7 @@ public class Spindexer { case UNKNOWN_START: // For now just set position ONE if UNKNOWN commandedIntakePosition = 0; - servos.setSpinPos(intakePositions[0]); + moveSpindexerToPos(intakePositions[0]); currentIntakeState = Spindexer.IntakeState.UNKNOWN_MOVE; break; case UNKNOWN_MOVE: @@ -348,7 +348,6 @@ public class Spindexer { if (ballPositions[0].isEmpty) { // Position 1 commandedIntakePosition = 0; - servos.setSpinPos(intakePositions[commandedIntakePosition]); currentIntakeState = Spindexer.IntakeState.MOVING; } //proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos); @@ -356,14 +355,12 @@ public class Spindexer { if (ballPositions[1].isEmpty) { // Position 2 commandedIntakePosition = 1; - servos.setSpinPos(intakePositions[commandedIntakePosition]); currentIntakeState = Spindexer.IntakeState.MOVING; } //proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos); if (ballPositions[2].isEmpty) { // Position 3 commandedIntakePosition = 2; - servos.setSpinPos(intakePositions[commandedIntakePosition]); currentIntakeState = Spindexer.IntakeState.MOVING; } if (currentIntakeState != Spindexer.IntakeState.MOVING) { @@ -422,17 +419,14 @@ public class Spindexer { 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? + } 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? + } else if (!ballPositions[2].isEmpty) { // Possible error: should it be !ballPosition[2].isEmpty? // Position 3 commandedIntakePosition = 2; - servos.setSpinPos(outakePositions[commandedIntakePosition]); currentIntakeState = Spindexer.IntakeState.SHOOTMOVING; } else { // Empty return to intake state @@ -452,21 +446,21 @@ public class Spindexer { break; case SHOOTWAIT: - // Stopping when we get to the new position] + // Stopping when we get to the new position if (prevIntakeState != currentIntakeState) { shootWaitCount = 0; } else { shootWaitCount++; } // wait 3 cycles - if ((shootWaitCount > 3) && (servos.spinEqual(intakePositions[commandedIntakePosition]))) { + if ((shootWaitCount > 15) && (servos.spinEqual(outakePositions[commandedIntakePosition]))) { currentIntakeState = Spindexer.IntakeState.SHOOTNEXT; ballPositions[commandedIntakePosition].isEmpty = true; //stopSpindexer(); //detectBalls(true, false); } else { // Keep moving the spindexer - moveSpindexerToPos(intakePositions[commandedIntakePosition]); + moveSpindexerToPos(outakePositions[commandedIntakePosition]); } break; From 641d947ec6bf6ce0eaf68ba1fe6badd09f2475f0 Mon Sep 17 00:00:00 2001 From: DanTheMan-byte Date: Wed, 28 Jan 2026 15:36:44 -0600 Subject: [PATCH 09/10] last edit --- .../ftc/teamcode/utils/Spindexer.java | 22 +++++++++---------- 1 file changed, 11 insertions(+), 11 deletions(-) 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 index c167a43..488c0e2 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java @@ -255,17 +255,17 @@ public class Spindexer { private void moveSpindexerToPos(double pos) { robot.spin1.setPosition(pos); robot.spin2.setPosition(1-pos); - double currentPos = servos.getSpinPos(); - if (!servos.spinEqual(pos) && Math.abs(prevPos - currentPos) <= 0){ - if (currentPos > pos){ - robot.spin1.setPosition(servos.getSpinPos() + 0.05); - robot.spin2.setPosition(1 - servos.getSpinPos() - 0.05); - } else { - robot.spin1.setPosition(servos.getSpinPos() - 0.05); - robot.spin2.setPosition(1 - servos.getSpinPos() + 0.05); - } - } - prevPos = currentPos; +// double currentPos = servos.getSpinPos(); +// if (!servos.spinEqual(pos) && Math.abs(prevPos - currentPos) <= 0){ +// if (currentPos > pos){ +// robot.spin1.setPosition(servos.getSpinPos() + 0.05); +// robot.spin2.setPosition(1 - servos.getSpinPos() - 0.05); +// } else { +// robot.spin1.setPosition(servos.getSpinPos() - 0.05); +// robot.spin2.setPosition(1 - servos.getSpinPos() + 0.05); +// } +// } +// prevPos = currentPos; } public void stopSpindexer() { From 159b130b5fcf793ad87aaa13264c20f17e535cf7 Mon Sep 17 00:00:00 2001 From: Matt9150 Date: Wed, 28 Jan 2026 17:33:37 -0600 Subject: [PATCH 10/10] Integrate shootAll on the Robot. This version was working except with 1 ball. --- .../teamcode/constants/ServoPositions.java | 12 ++++---- .../ftc/teamcode/teleop/TeleopV3.java | 12 ++++---- .../ftc/teamcode/utils/Spindexer.java | 30 +++++++++---------- 3 files changed, 27 insertions(+), 27 deletions(-) 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 9652da6..3fa4906 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 @@ -5,16 +5,16 @@ import com.acmerobotics.dashboard.config.Config; @Config public class ServoPositions { - public static double spindexer_intakePos1 = 0.00; //0.13; + public static double spindexer_intakePos1 = 0.05; //0.13; - public static double spindexer_intakePos2 = 0.19; //0.33;//0.5; + public static double spindexer_intakePos2 = 0.24; //0.33;//0.5; - public static double spindexer_intakePos3 = 0.38; //0.53;//0.66; + public static double spindexer_intakePos3 = 0.43; //0.53;//0.66; - public static double spindexer_outtakeBall3 = 0.65; //0.65; //0.24; + public static double spindexer_outtakeBall3 = 0.70; //0.65; //0.24; - public static double spindexer_outtakeBall2 = 0.46; //0.46; //0.6; - public static double spindexer_outtakeBall1 = 0.27; //0.27; //0.4; + public static double spindexer_outtakeBall2 = 0.51; //0.46; //0.6; + public static double spindexer_outtakeBall1 = 0.32; //0.27; //0.4; public static double spinStartPos = spindexer_outtakeBall3 - 0.1; 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 f5e77d5..567cf73 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 @@ -633,25 +633,25 @@ public class TeleopV3 extends LinearOpMode { // TELE.addLine("shooting"); // } if (shooterTicker == 0) { - shooterTicker++; spindexer.prepareShootAll(); + TELE.addLine("preparing to shoot"); + } else if (shooterTicker == 2) { + robot.transferServo.setPosition(transferServo_in); + spindexer.shootAll(); TELE.addLine("starting to shoot"); } else if (!spindexer.shootAllComplete()) { robot.transferServo.setPosition(transferServo_in); - shooterTicker++; - spindexer.shootAll(); TELE.addLine("shoot"); } else { robot.transferServo.setPosition(transferServo_out); //spindexPos = spindexer_intakePos1; - shootAll = false; - spindexer.resetSpindexer(); //spindexer.processIntake(); TELE.addLine("stop shooting"); } - spindexer.processIntake(); + shooterTicker++; + //spindexer.processIntake(); } if (gamepad1.left_stick_button){ 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 index 488c0e2..79dcab3 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Spindexer.java @@ -343,21 +343,21 @@ public class Spindexer { // Find Next Open Position and start movement double currentSpindexerPos = servos.getSpinPos(); double commandedtravelDistance = 2.0; - //double proposedTravelDistance = Math.abs(intakePositions[0] - currentSpindexerPos); + double proposedTravelDistance = Math.abs(intakePositions[0] - currentSpindexerPos); //if (ballPositions[0].isEmpty && (proposedTravelDistance < commandedtravelDistance)) { if (ballPositions[0].isEmpty) { // Position 1 commandedIntakePosition = 0; currentIntakeState = Spindexer.IntakeState.MOVING; } - //proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos); + proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos); //if (ballPositions[1].isEmpty && (proposedTravelDistance < commandedtravelDistance)) { if (ballPositions[1].isEmpty) { // Position 2 commandedIntakePosition = 1; currentIntakeState = Spindexer.IntakeState.MOVING; } - //proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos); + proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos); if (ballPositions[2].isEmpty) { // Position 3 commandedIntakePosition = 2; @@ -416,18 +416,18 @@ public class Spindexer { case SHOOTNEXT: // Find Next Open Position and start movement - if (!ballPositions[0].isEmpty) { + if (!ballPositions[1].isEmpty) { // Position 1 - commandedIntakePosition = 0; - currentIntakeState = Spindexer.IntakeState.SHOOTMOVING; - } else if (!ballPositions[1].isEmpty) { // Possible error: should it be !ballPosition[1].isEmpty? - // Position 2 commandedIntakePosition = 1; currentIntakeState = Spindexer.IntakeState.SHOOTMOVING; - } else if (!ballPositions[2].isEmpty) { // Possible error: should it be !ballPosition[2].isEmpty? - // Position 3 + } else if (!ballPositions[2].isEmpty) { + // Position 2 commandedIntakePosition = 2; currentIntakeState = Spindexer.IntakeState.SHOOTMOVING; + } else if (!ballPositions[0].isEmpty) { + // Position 3 + commandedIntakePosition = 0; + currentIntakeState = Spindexer.IntakeState.SHOOTMOVING; } else { // Empty return to intake state currentIntakeState = IntakeState.FINDNEXT; @@ -452,16 +452,16 @@ public class Spindexer { } else { shootWaitCount++; } - // wait 3 cycles - if ((shootWaitCount > 15) && (servos.spinEqual(outakePositions[commandedIntakePosition]))) { + // wait 10 cycles + if (shootWaitCount > 2) { currentIntakeState = Spindexer.IntakeState.SHOOTNEXT; ballPositions[commandedIntakePosition].isEmpty = true; + shootWaitCount = 0; //stopSpindexer(); //detectBalls(true, false); - } else { - // Keep moving the spindexer - moveSpindexerToPos(outakePositions[commandedIntakePosition]); } + // Keep moving the spindexer + moveSpindexerToPos(outakePositions[commandedIntakePosition]+(shootWaitCount*0.01)); break; default: