From 05499025057fec4a278ab85b6c7e53511f992ea6 Mon Sep 17 00:00:00 2001 From: DanTheMan-byte Date: Tue, 27 Jan 2026 15:54:08 -0600 Subject: [PATCH] a lot of changes happened in a galaxy far far away --- .../ftc/teamcode/autonomous/AutoClose_V3.java | 16 +- .../ftc/teamcode/autonomous/AutoFar_V1.java | 19 +- .../autonomous/ProtoAutoClose_V3.java | 44 ++-- .../ftc/teamcode/constants/Color.java | 1 + .../teamcode/constants/ServoPositions.java | 14 +- .../ftc/teamcode/teleop/TeleopV2.java | 8 +- .../ftc/teamcode/teleop/TeleopV3.java | 236 ++++++++++-------- .../ftc/teamcode/tests/IntakeTest.java | 23 +- .../ftc/teamcode/tests/PIDServoTest.java | 6 +- .../ftc/teamcode/tests/ShooterTest.java | 27 +- .../utils/PositionalServoProgrammer.java | 25 +- .../ftc/teamcode/utils/Robot.java | 16 +- .../ftc/teamcode/utils/Servos.java | 11 +- .../ftc/teamcode/utils/Spindexer.java | 38 ++- 14 files changed, 259 insertions(+), 225 deletions(-) diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/AutoClose_V3.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/AutoClose_V3.java index 1bcee9e..d4af8e7 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/AutoClose_V3.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/AutoClose_V3.java @@ -133,8 +133,8 @@ public class AutoClose_V3 extends LinearOpMode { robot.shooter2.setPower(powPID); spinPID = servo.setSpinPos(spindexer); - robot.spin1.setPower(spinPID); - robot.spin2.setPower(-spinPID); + robot.spin1.setPosition(spinPID); + robot.spin2.setPosition(-spinPID); TELE.addData("Velocity", velo); TELE.addLine("spindex"); TELE.update(); @@ -143,8 +143,8 @@ public class AutoClose_V3 extends LinearOpMode { teleStart = drive.localizer.getPose(); if (servo.spinEqual(spindexer)){ - robot.spin1.setPower(0); - robot.spin2.setPower(0); + robot.spin1.setPosition(0); + robot.spin2.setPosition(0); return false; } else { return true; @@ -224,8 +224,8 @@ public class AutoClose_V3 extends LinearOpMode { if (!servo.spinEqual(position)){ double spinPID = servo.setSpinPos(position); - robot.spin1.setPower(spinPID); - robot.spin2.setPower(-spinPID); + robot.spin1.setPosition(spinPID); + robot.spin2.setPosition(-spinPID); } if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){ @@ -259,8 +259,8 @@ public class AutoClose_V3 extends LinearOpMode { robot.intake.setPower(1); if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) { - robot.spin1.setPower(0); - robot.spin2.setPower(0); + robot.spin1.setPosition(0); + robot.spin2.setPosition(0); if (getRuntime() - stamp - intakeTime < 1){ pow = -2*(getRuntime() - stamp - intakeTime); return true; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/AutoFar_V1.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/AutoFar_V1.java index 1dc53eb..5ec38d6 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/AutoFar_V1.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/autonomous/AutoFar_V1.java @@ -31,8 +31,7 @@ import org.firstinspires.ftc.teamcode.utils.Servos; import java.util.List; -@Config -@Autonomous(preselectTeleOp = "TeleopV3") + public class AutoFar_V1 extends LinearOpMode { Robot robot; MultipleTelemetry TELE; @@ -133,8 +132,8 @@ public class AutoFar_V1 extends LinearOpMode { robot.shooter2.setPower(powPID); spinPID = servo.setSpinPos(spindexer); - robot.spin1.setPower(spinPID); - robot.spin2.setPower(-spinPID); + robot.spin1.setPosition(spinPID); + robot.spin2.setPosition(-spinPID); TELE.addData("Velocity", velo); TELE.addLine("spindex"); TELE.update(); @@ -143,8 +142,8 @@ public class AutoFar_V1 extends LinearOpMode { teleStart = drive.localizer.getPose(); if (servo.spinEqual(spindexer)){ - robot.spin1.setPower(0); - robot.spin2.setPower(0); + robot.spin1.setPosition(0); + robot.spin2.setPosition(0); return false; } else { return true; @@ -224,8 +223,8 @@ public class AutoFar_V1 extends LinearOpMode { if (!servo.spinEqual(position)){ double spinPID = servo.setSpinPos(position); - robot.spin1.setPower(spinPID); - robot.spin2.setPower(-spinPID); + robot.spin1.setPosition(spinPID); + robot.spin2.setPosition(-spinPID); } if (s1D < 43 && servo.spinEqual(position) && getRuntime() - stamp > 0.5){ @@ -259,8 +258,8 @@ public class AutoFar_V1 extends LinearOpMode { robot.intake.setPower(1); if ((s1D < 43.0 && s2D < 60.0 && s3D < 33.0) || getRuntime() - stamp > intakeTime) { - robot.spin1.setPower(0); - robot.spin2.setPower(0); + robot.spin1.setPosition(0); + robot.spin2.setPosition(0); if (getRuntime() - stamp - intakeTime < 1){ pow = -2*(getRuntime() - stamp - intakeTime); return true; 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 a18be3f..ccf2421 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 @@ -182,8 +182,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode { velo = flywheel.getVelo(); spinPID = servo.setSpinPos(spindexer); - robot.spin1.setPower(spinPID); - robot.spin2.setPower(-spinPID); + robot.spin1.setPosition(spinPID); + robot.spin2.setPosition(-spinPID); TELE.addData("Velocity", velo); TELE.addLine("spindex"); TELE.update(); @@ -192,8 +192,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode { teleStart = drive.localizer.getPose(); if (servo.spinEqual(spindexer)) { - robot.spin1.setPower(0); - robot.spin2.setPower(0); + robot.spin1.setPosition(0); + robot.spin2.setPosition(0); return false; } else { @@ -240,8 +240,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode { robot.transferServo.setPosition(transferServo_in); - robot.spin1.setPower(-spinPow); - robot.spin2.setPower(spinPow); + robot.spin1.setPosition(-spinPow); + robot.spin2.setPosition(spinPow); return true; } else { @@ -271,12 +271,12 @@ public class ProtoAutoClose_V3 extends LinearOpMode { if (ticker % 12 < 6) { - robot.spin1.setPower(-1); - robot.spin2.setPower(1); + robot.spin1.setPosition(-1); + robot.spin2.setPosition(1); } else { - robot.spin1.setPower(1); - robot.spin2.setPower(-1); + robot.spin1.setPosition(1); + robot.spin2.setPosition(-1); } if (getRuntime() - stamp > jamTime+0.4) { @@ -317,20 +317,20 @@ public class ProtoAutoClose_V3 extends LinearOpMode { if (ticker % 60 < 12) { - robot.spin1.setPower(-1); - robot.spin2.setPower(1); + robot.spin1.setPosition(-1); + robot.spin2.setPosition(1); } else if (ticker % 60 < 30) { - robot.spin1.setPower(-0.5); - robot.spin2.setPower(0.5); + robot.spin1.setPosition(-0.5); + robot.spin2.setPosition(0.5); } else if (ticker % 60 < 42) { - robot.spin1.setPower(1); - robot.spin2.setPower(-1); + robot.spin1.setPosition(1); + robot.spin2.setPosition(-1); } else { - robot.spin1.setPower(0.5); - robot.spin2.setPower(-0.5); + robot.spin1.setPosition(0.5); + robot.spin2.setPosition(-0.5); } robot.intake.setPower(1); TELE.addData("Reverse?", reverse); @@ -338,11 +338,11 @@ public class ProtoAutoClose_V3 extends LinearOpMode { if (getRuntime() - stamp > intakeTime) { if (reverse) { - robot.spin1.setPower(-1); - robot.spin2.setPower(1); + robot.spin1.setPosition(-1); + robot.spin2.setPosition(1); } else { - robot.spin1.setPower(1); - robot.spin2.setPower(-1); + robot.spin1.setPosition(1); + robot.spin2.setPosition(-1); } return false; } else { diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Color.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Color.java index aabb7b5..6d06db6 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Color.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/constants/Color.java @@ -2,4 +2,5 @@ package org.firstinspires.ftc.teamcode.constants; public class Color { public static boolean redAlliance = true; + public static double Light0 = 0.28, Light1 = 0.67, Light2 = 0.36, Light3 = 0.5; } 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 a755589..63a5661 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,18 @@ import com.acmerobotics.dashboard.config.Config; @Config public class ServoPositions { - public static double spindexer_intakePos1 = 0.18; + public static double spindexer_intakePos1 = 0.13; - public static double spindexer_intakePos2 = 0.36;//0.5; + public static double spindexer_intakePos2 = 0.33;//0.5; - public static double spindexer_intakePos3 = 0.54;//0.66; + public static double spindexer_intakePos3 = 0.53;//0.66; - public static double spindexer_outtakeBall3 = 0.47; + public static double spindexer_outtakeBall3 = 0.8; + + 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 spindexer_outtakeBall2 = 0.31; - public static double spindexer_outtakeBall1 = 0.15; public static double transferServo_out = 0.15; 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 4212355..187896f 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 @@ -162,11 +162,11 @@ public class TeleopV2 extends LinearOpMode { //TODO: make sure changing position works throughout opmode if (!servo.spinEqual(spindexPos)){ spindexPID = servo.setSpinPos(spindexPos); - robot.spin1.setPower(spindexPID); - robot.spin2.setPower(-spindexPID); + robot.spin1.setPosition(spindexPID); + robot.spin2.setPosition(-spindexPID); } else{ - robot.spin1.setPower(0); - robot.spin2.setPower(0); + robot.spin1.setPosition(0); + robot.spin2.setPosition(0); } //INTAKE: 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 e234fcd..d4d3aac 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 @@ -1,6 +1,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.transferServo_in; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out; @@ -121,6 +122,7 @@ public class TeleopV3 extends LinearOpMode { private int tickerA = 1; private boolean transferIn = false; boolean turretInterpolate = false; + public static double spinSpeedIncrease = 0.04; public static double velPrediction(double distance) { if (distance < 30) { @@ -139,13 +141,15 @@ public class TeleopV3 extends LinearOpMode { @Override public void runOpMode() throws InterruptedException { + robot = new Robot(hardwareMap); + robot.light.setPosition(0); List allHubs = hardwareMap.getAll(LynxModule.class); for (LynxModule hub : allHubs) { hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL); } - robot = new Robot(hardwareMap); + TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry()); servo = new Servos(hardwareMap); flywheel = new Flywheel(hardwareMap); @@ -167,14 +171,16 @@ public class TeleopV3 extends LinearOpMode { // robot.limelight.start(); Turret turret = new Turret(robot, TELE, robot.limelight); - waitForStart(); - + robot.light.setPosition(1); waitForStart(); if (isStopRequested()) return; robot.transferServo.setPosition(transferServo_out); while (opModeIsActive()) { + // LIGHT COLORS + spindexer.ballCounterLight(); + //DRIVETRAIN: double y = 0.0; @@ -233,37 +239,43 @@ public class TeleopV3 extends LinearOpMode { //TODO: Use color sensors to switch between positions...switch after ball detected in + if (gamepad1.right_bumper){ + shootAll = false; + robot.transferServo.setPosition(transferServo_out); + + } + if (autoSpintake) { if (!servo.spinEqual(spindexPos) && !gamepad1.right_bumper) { - spinCurrentPos = servo.getSpinPos(); - double spindexPID = spinPID.calculate(spinCurrentPos, spindexPos); - robot.spin1.setPower(spindexPID); - robot.spin2.setPower(-spindexPID); + robot.spin1.setPosition(spindexPos); + robot.spin2.setPosition(1-spindexPos); } if (gamepad1.right_bumper) { + shootAll = false; + intakeTicker++; - if (intakeTicker % 20 < 2) { - - robot.spin1.setPower(-1); - robot.spin2.setPower(1); - - } else if (intakeTicker % 20 < 10) { - robot.spin1.setPower(-0.5); - robot.spin2.setPower(0.5); - } else if (intakeTicker % 20 < 12) { - robot.spin1.setPower(1); - robot.spin2.setPower(-1); - } else { - robot.spin1.setPower(0.5); - robot.spin2.setPower(-0.5); - } +// if (intakeTicker % 20 < 2) { +// +// robot.spin1.setPower(-1); +// robot.spin2.setPower(1); +// +// } else if (intakeTicker % 20 < 10) { +// robot.spin1.setPower(-0.5); +// robot.spin2.setPower(0.5); +// } else if (intakeTicker % 20 < 12) { +// robot.spin1.setPower(1); +// robot.spin2.setPower(-1); +// } else { +// robot.spin1.setPower(0.5); +// robot.spin2.setPower(-0.5); +// } robot.intake.setPower(1); intakeStamp = getRuntime(); @@ -271,17 +283,9 @@ public class TeleopV3 extends LinearOpMode { TELE.update(); } else { if (!servo.spinEqual(spindexPos)) { - spinCurrentPos = servo.getSpinPos(); + robot.spin1.setPosition(spindexPos); + robot.spin2.setPosition(1-spindexPos); - double spindexPID = spinPID.calculate(spinCurrentPos, spindexPos); - - robot.spin1.setPower(spindexPID); - robot.spin2.setPower(-spindexPID); - - } else { - - robot.spin1.setPower(0); - robot.spin2.setPower(0); } spindexPos = spindexer_intakePos1; @@ -506,76 +510,76 @@ public class TeleopV3 extends LinearOpMode { // } // } - if (gamepad1.left_bumper && !enableSpindexerManager) { + //if (gamepad1.left_bumper && !enableSpindexerManager) { - robot.transferServo.setPosition(transferServo_out); + // robot.transferServo.setPosition(transferServo_out); - autoSpintake = false; - - intakeTicker++; - - if (intakeTicker % 10 < 1) { - - robot.spin1.setPower(-1); - robot.spin2.setPower(1); - - } else if (intakeTicker % 10 < 5) { - robot.spin1.setPower(-0.5); - robot.spin2.setPower(0.5); - } else if (intakeTicker % 10 < 6) { - robot.spin1.setPower(1); - robot.spin2.setPower(-1); - } else { - robot.spin1.setPower(0.5); - robot.spin2.setPower(-0.5); - } - - intake = false; - reject = false; - - robot.intake.setPower(0.5); - - } - - if (gamepad1.leftBumperWasReleased() && !enableSpindexerManager) { - shootStamp = getRuntime(); - shootAll = true; - - shooterTicker = 0; - } - - if (shootAll && !enableSpindexerManager) { - - TELE.addData("100% works", shootOrder); - - intake = false; - reject = false; - - shooterTicker++; - - spindexPos = spindexer_intakePos1; - - if (getRuntime() - shootStamp < 3.5) { - - robot.transferServo.setPosition(transferServo_in); - - autoSpintake = false; - - robot.spin1.setPower(-spinPow); - robot.spin2.setPower(spinPow); - - } else { - robot.transferServo.setPosition(transferServo_out); - spindexPos = spindexer_intakePos1; - - shootAll = false; - - autoSpintake = true; - - robot.transferServo.setPosition(transferServo_out); - } - - } +// autoSpintake = false; +// +// intakeTicker++; +// +// if (intakeTicker % 10 < 1) { +// +// robot.spin1.setPower(-1); +// robot.spin2.setPower(1); +// +// } else if (intakeTicker % 10 < 5) { +// robot.spin1.setPower(-0.5); +// robot.spin2.setPower(0.5); +// } else if (intakeTicker % 10 < 6) { +// robot.spin1.setPower(1); +// robot.spin2.setPower(-1); +// } else { +// robot.spin1.setPower(0.5); +// robot.spin2.setPower(-0.5); +// } +// +// intake = false; +// reject = false; +// +// robot.intake.setPower(0.5); +// +// } +// +// if (gamepad1.leftBumperWasReleased() && !enableSpindexerManager) { +// shootStamp = getRuntime(); +// shootAll = true; +// +// shooterTicker = 0; +// } +// +// if (shootAll && !enableSpindexerManager) { +// +// TELE.addData("100% works", shootOrder); +// +// intake = false; +// reject = false; +// +// shooterTicker++; +// +// spindexPos = spindexer_intakePos1; +// +// if (getRuntime() - shootStamp < 3.5) { +// +// robot.transferServo.setPosition(transferServo_in); +// +// autoSpintake = false; +// +// robot.spin1.setPower(-spinPow); +// robot.spin2.setPower(spinPow); +// +// } else { +// robot.transferServo.setPosition(transferServo_out); +// spindexPos = spindexer_intakePos1; +// +// shootAll = false; +// +// autoSpintake = true; +// +// robot.transferServo.setPosition(transferServo_out); +// } +// +// } if (enableSpindexerManager) { if (!shootAll) { @@ -599,6 +603,8 @@ public class TeleopV3 extends LinearOpMode { shootAll = true; shooterTicker = 0; + spindexPos = spinStartPos;// TODO: Change starting position based on desired order to shoot green ball + } if (shootAll) { @@ -606,17 +612,18 @@ public class TeleopV3 extends LinearOpMode { 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); + if (shooterTicker == 0 && !servo.spinEqual(spindexPos)){ + robot.spin1.setPosition(spindexPos); + robot.spin2.setPosition(1-spindexPos); + } else { + robot.transferServo.setPosition(transferServo_in); + shooterTicker++; + double prevSpinPos = robot.spin1.getPosition(); + robot.spin1.setPosition(prevSpinPos + spinSpeedIncrease); + robot.spin2.setPosition(1 - prevSpinPos - spinSpeedIncrease); + } } else { robot.transferServo.setPosition(transferServo_out); @@ -624,12 +631,19 @@ public class TeleopV3 extends LinearOpMode { shootAll = false; - robot.transferServo.setPosition(transferServo_out); - spindexer.resetSpindexer(); spindexer.processIntake(); } } + + if (gamepad1.left_stick_button){ + robot.transferServo.setPosition(transferServo_out); + //spindexPos = spindexer_intakePos1; + + shootAll = false; + spindexer.resetSpindexer(); + spindexer.processIntake(); + } } // diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/IntakeTest.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/IntakeTest.java index b55608c..a1dffd3 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/IntakeTest.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/IntakeTest.java @@ -16,8 +16,7 @@ import org.firstinspires.ftc.teamcode.utils.Servos; import java.util.ArrayList; import java.util.List; -@Config -@TeleOp + public class IntakeTest extends LinearOpMode { Robot robot; MultipleTelemetry TELE; @@ -72,19 +71,19 @@ public class IntakeTest extends LinearOpMode { initPos = currentPos; } if (reverse){ - robot.spin1.setPower(manualPow); - robot.spin2.setPower(-manualPow); + robot.spin1.setPosition(manualPow); + robot.spin2.setPosition(-manualPow); } else { - robot.spin1.setPower(-manualPow); - robot.spin2.setPower(manualPow); + robot.spin1.setPosition(-manualPow); + robot.spin2.setPosition(manualPow); } robot.intake.setPower(1); stamp = getRuntime(); TELE.addData("Reverse?", reverse); TELE.update(); } else { - robot.spin1.setPower(0); - robot.spin2.setPower(0); + robot.spin1.setPosition(0); + robot.spin2.setPosition(0); if (getRuntime() - stamp < 1) { robot.intake.setPower(-(getRuntime() - stamp)*2); @@ -191,15 +190,15 @@ public class IntakeTest extends LinearOpMode { if (!atTarget) { powPID = servo.setSpinPos(spindexerPos); - robot.spin1.setPower(powPID); - robot.spin2.setPower(-powPID); + robot.spin1.setPosition(powPID); + robot.spin2.setPosition(-powPID); steadySpin = false; wasMoving = true; // remember we were moving stamp = getRuntime(); } else { - robot.spin1.setPower(0); - robot.spin2.setPower(0); + robot.spin1.setPosition(0); + robot.spin2.setPosition(0); steadySpin = true; wasMoving = false; } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/PIDServoTest.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/PIDServoTest.java index 303544d..4b6c5df 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/PIDServoTest.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/PIDServoTest.java @@ -9,8 +9,6 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import org.firstinspires.ftc.teamcode.utils.Robot; -@TeleOp -@Config public class PIDServoTest extends LinearOpMode { public static double p = 2, i = 0, d = 0, f = 0; @@ -47,8 +45,8 @@ public class PIDServoTest extends LinearOpMode { double pid = controller.calculate(pos, target); - robot.spin1.setPower(pid); - robot.spin2.setPower(-pid); + robot.spin1.setPosition(pid); + robot.spin2.setPosition(-pid); } telemetry.addData("pos", pos); 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 39f1a50..d45ffc0 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 @@ -1,8 +1,11 @@ package org.firstinspires.ftc.teamcode.tests; +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_outtakeBall1; 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.teleop.TeleopV3.spinSpeedIncrease; import com.acmerobotics.dashboard.FtcDashboard; import com.acmerobotics.dashboard.config.Config; @@ -13,6 +16,7 @@ import com.qualcomm.robotcore.hardware.DcMotorEx; 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; @Config @@ -36,6 +40,7 @@ public class ShooterTest extends LinearOpMode { public static boolean intake = false; Robot robot; Flywheel flywheel; + Servos servo; double shootStamp = 0.0; boolean shootAll = false; @@ -45,6 +50,7 @@ public class ShooterTest extends LinearOpMode { public static boolean enableHoodAutoOpen = false; public double hoodAdjust = 0.0; public static double hoodAdjustFactor = 1.0; + private int shooterTicker = 0; Spindexer spindexer ; @Override @@ -55,6 +61,7 @@ public class ShooterTest extends LinearOpMode { DcMotorEx rightShooter = robot.shooter2; flywheel = new Flywheel(hardwareMap); spindexer = new Spindexer(hardwareMap); + servo = new Servos(hardwareMap); MultipleTelemetry TELE = new MultipleTelemetry( telemetry, FtcDashboard.getInstance().getTelemetry() @@ -95,6 +102,7 @@ public class ShooterTest extends LinearOpMode { shootAll = true; shoot = false; robot.transfer.setPower(transferPower); + shooterTicker = 0; } if (shootAll) { @@ -103,24 +111,31 @@ public class ShooterTest extends LinearOpMode { // 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); + if (shooterTicker == 0 && !servo.spinEqual(spinStartPos)){ + robot.spin1.setPosition(spinStartPos); + robot.spin2.setPosition(1-spinStartPos); + } else { + robot.transferServo.setPosition(transferServo_in); + shooterTicker++; + double prevSpinPos = robot.spin1.getPosition(); + robot.spin1.setPosition(prevSpinPos + spinSpeedIncrease); + robot.spin2.setPosition(1 - prevSpinPos - spinSpeedIncrease); + } + - robot.spin1.setPower(-spinPow); - robot.spin2.setPower(spinPow); } else { robot.transferServo.setPosition(transferServo_out); //spindexPos = spindexer_intakePos1; shootAll = false; + shooterTicker = 0; robot.transferServo.setPosition(transferServo_out); robot.transfer.setPower(0); - robot.spin1.setPower(0); - robot.spin2.setPower(0); + spindexer.resetSpindexer(); spindexer.processIntake(); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/PositionalServoProgrammer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/PositionalServoProgrammer.java index f986be2..18e229a 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/PositionalServoProgrammer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/PositionalServoProgrammer.java @@ -18,14 +18,10 @@ public class PositionalServoProgrammer extends LinearOpMode { Servos servo; public static double spindexPos = 0.501; - public static double spindexPow = 0.0; - public static double spinHoldPow = 0.0; public static double turretPos = 0.501; - public static double turretPow = 0.0; - public static double turrHoldPow = 0.0; public static double transferPos = 0.501; public static double hoodPos = 0.501; - public static int mode = 0; //0 for positional, 1 for power + public static double light = 0.501; Turret turret; @@ -35,22 +31,13 @@ public class PositionalServoProgrammer extends LinearOpMode { TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry()); servo = new Servos(hardwareMap); - - turret = new Turret(robot, TELE, robot.limelight ); waitForStart(); if (isStopRequested()) return; while (opModeIsActive()){ - if (spindexPos != 0.501 && !servo.spinEqual(spindexPos) && mode == 0){ - double pos = servo.setSpinPos(spindexPos); - robot.spin1.setPower(pos); - robot.spin2.setPower(-pos); - } else if (mode == 0){ - robot.spin1.setPower(spinHoldPow); - robot.spin2.setPower(spinHoldPow); - } else { - robot.spin1.setPower(spindexPow); - robot.spin2.setPower(-spindexPow); + if (spindexPos != 0.501 && !servo.spinEqual(spindexPos)){ + robot.spin1.setPosition(spindexPos); + robot.spin2.setPosition(1-spindexPos); } if (turretPos != 0.501){ robot.turr1.setPosition(turretPos); @@ -62,6 +49,9 @@ public class PositionalServoProgrammer extends LinearOpMode { if (hoodPos != 0.501){ robot.hood.setPosition(hoodPos); } + if (light !=0.501){ + robot.light.setPosition(light); + } // To check configuration of spindexer: // Set "mode" to 1 and spindexPow to 0.1 // If the spindexer is turning clockwise, the servos are reversed. Swap the configuration of the two servos, DO NOT TOUCH THE ACTUAL CODE @@ -79,7 +69,6 @@ public class PositionalServoProgrammer extends LinearOpMode { TELE.addData("spindexer voltage 2", robot.spin2Pos.getVoltage()); TELE.addData("hood pos", robot.hood.getPosition()); TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage()); - TELE.addData("spindexer pow", robot.spin1.getPower()); TELE.addData("tpos ", turret.getTurrPos() ); TELE.update(); } 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 f15d03b..bbe7192 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 @@ -40,8 +40,10 @@ public class Robot { public Servo transferServo; public Servo turr1; public Servo turr2; - public CRServo spin1; - public CRServo spin2; + + public Servo spin1; + + public Servo spin2; public AnalogInput spin1Pos; public AnalogInput spin2Pos; public AnalogInput turr1Pos; @@ -52,6 +54,7 @@ public class Robot { public RevColorSensorV3 color2; public RevColorSensorV3 color3; public Limelight3A limelight; + public Servo light; public Robot(HardwareMap hardwareMap) { @@ -93,17 +96,14 @@ public class Robot { turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // Encoder of turret plugged in intake port //TODO: check spindexer configuration (both servo and analog input) - check comments in PositionalServoProgrammer - spin1 = hardwareMap.get(CRServo.class, "spin1"); + spin1 = hardwareMap.get(Servo.class, "spin2"); spin1Pos = hardwareMap.get(AnalogInput.class, "spin1Pos"); - spin2 = hardwareMap.get(CRServo.class, "spin2"); + spin2 = hardwareMap.get(Servo.class, "spin1"); spin2Pos = hardwareMap.get(AnalogInput.class, "spin2Pos"); - spin1.setDirection(DcMotorSimple.Direction.REVERSE); - spin2.setDirection(DcMotorSimple.Direction.REVERSE); - transfer = hardwareMap.get(DcMotorEx.class, "transfer"); transferServo = hardwareMap.get(Servo.class, "transferServo"); @@ -125,5 +125,7 @@ public class Robot { webcam = hardwareMap.get(WebcamName.class, "Webcam 1"); aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults(); } + + light = hardwareMap.get(Servo.class, "light"); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Servos.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Servos.java index f185ac0..324a36f 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Servos.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Servos.java @@ -10,8 +10,8 @@ public class Servos { // TODO: get PIDF constants public static double spinP = 2.0, spinI = 0, spinD = 0.3, spinF = 0.02; public static double turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0; - public static double spin_scalar = 1.0086; - public static double spin_restPos = 0.0; + public static double spin_scalar = 1.112; + public static double spin_restPos = 0.155; public static double turret_scalar = 1.009; public static double turret_restPos = 0.0; Robot robot; @@ -27,16 +27,14 @@ public class Servos { } // In the code below, encoder = robot.servo.getVoltage() - + // TODO: set the restPos and scalar public double getSpinPos() { return spin_scalar * ((robot.spin1Pos.getVoltage() - spin_restPos) / 3.3); } - //TODO: PID warp so 0 and 1 are usable positions public double setSpinPos(double pos) { - spinPID.setPIDF(spinP, spinI, spinD, spinF); - return spinPID.calculate(this.getSpinPos(), pos); + return pos; } public boolean spinEqual(double pos) { @@ -45,7 +43,6 @@ public class Servos { public double getTurrPos() { return 1.0; - } public double setTurrPos(double pos) { 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 9e28ed0..4496cae 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 @@ -4,6 +4,7 @@ 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.Color.*; 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; @@ -67,7 +68,7 @@ public class Spindexer { SHOOTWAIT, SHOOT_ALL_PREP, SHOOT_ALL_READY - }; + } public IntakeState currentIntakeState = IntakeState.UNKNOWN_START; public int unknownColorDetect = 0; @@ -75,7 +76,7 @@ public class Spindexer { UNKNOWN, GREEN, PURPLE - }; + } class BallPosition { boolean isEmpty = true; @@ -247,17 +248,34 @@ public class Spindexer { } public void moveSpindexerToPos(double pos) { - spinCurrentPos = servos.getSpinPos(); - - double spindexPID = spinPID.calculate(spinCurrentPos, pos); - - robot.spin1.setPower(spindexPID); - robot.spin2.setPower(-spindexPID); + robot.spin1.setPosition(pos); + robot.spin2.setPosition(1-pos); } public void stopSpindexer() { - robot.spin1.setPower(0); - robot.spin2.setPower(0); + + } + + public void ballCounterLight(){ + int counter = 0; + if (!ballPositions[0].isEmpty){ + counter++; + } + if (!ballPositions[1].isEmpty){ + counter++; + } + if (!ballPositions[2].isEmpty){ + counter++; + } + if (counter == 3){ + robot.light.setPosition(Light3); + } else if (counter == 2){ + robot.light.setPosition(Light2); + } else if (counter == 1){ + robot.light.setPosition(Light1); + } else { + robot.light.setPosition(Light0); + } } public boolean isFull () {