8 Commits

Author SHA1 Message Date
209c34b3fd Merge remote-tracking branch 'origin/danielv5' into update-teleop
# Conflicts:
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/NewShooterTest.java
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utilsv2/Shooter.java
2026-06-03 14:12:26 -05:00
d8cf594828 Fix some intrinsic bugs, refactor constructor in shooter 2026-06-03 14:08:49 -05:00
e658ec044c fixed issue - two flywheel instances created a conflict 2026-06-03 10:20:13 -05:00
12e5fba938 fixed issue - two flywheel instances created a conflict 2026-06-03 10:18:13 -05:00
47c505742a fixes to flywheel in order to operate more globally 2026-06-03 10:03:34 -05:00
c8e9be1c08 Merge remote-tracking branch 'origin/danielv5' into danielv5 2026-06-03 00:22:11 -05:00
28451ce26d auto coded 2026-06-03 00:21:51 -05:00
9c3b4c2010 Add beam break sensors to Hardware_Tester 2026-06-03 00:04:20 -05:00
7 changed files with 438 additions and 391 deletions

View File

@@ -1,341 +1,366 @@
//package org.firstinspires.ftc.teamcode.autonomous; package org.firstinspires.ftc.teamcode.autonomous;
//
//import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos; import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
//import static org.firstinspires.ftc.teamcode.utils.Targeting.turretInterpolate; import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseH;
//import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed; import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseY;
//import static org.firstinspires.ftc.teamcode.utils.Turret.turrDefault; import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseX;
//import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseH;
//import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseY; import com.acmerobotics.dashboard.FtcDashboard;
//import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseX; import com.acmerobotics.dashboard.config.Config;
// import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
//import com.acmerobotics.dashboard.FtcDashboard; import com.pedropathing.follower.Follower;
//import com.acmerobotics.dashboard.config.Config; import com.pedropathing.geometry.BezierCurve;
//import com.acmerobotics.dashboard.telemetry.MultipleTelemetry; import com.pedropathing.geometry.BezierLine;
//import com.pedropathing.follower.Follower; import com.pedropathing.geometry.Pose;
//import com.pedropathing.geometry.BezierCurve; import com.pedropathing.paths.PathChain;
//import com.pedropathing.geometry.BezierLine; import com.qualcomm.hardware.lynx.LynxModule;
//import com.pedropathing.geometry.Pose; import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
//import com.pedropathing.paths.PathChain; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
//import com.qualcomm.hardware.lynx.LynxModule;
//import com.qualcomm.robotcore.eventloop.opmode.Autonomous; import org.firstinspires.ftc.teamcode.constants.Color;
//import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
// import org.firstinspires.ftc.teamcode.utilsv2.Flywheel;
//import org.firstinspires.ftc.teamcode.constants.Color; import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes;
//import org.firstinspires.ftc.teamcode.pedroPathing.Constants; import org.firstinspires.ftc.teamcode.utilsv2.Robot;
//import org.firstinspires.ftc.teamcode.utilsv2.Flywheel; import org.firstinspires.ftc.teamcode.utilsv2.Turret;
//import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes;
//import org.firstinspires.ftc.teamcode.utilsv2.Robot; import java.util.List;
//import org.firstinspires.ftc.teamcode.utils.Servos;
//import org.firstinspires.ftc.teamcode.utils.Spindexer; @Config
//import org.firstinspires.ftc.teamcode.utils.Targeting; @Autonomous (preselectTeleOp = "TeleopV4")
//import org.firstinspires.ftc.teamcode.utilsv2.Turret; public class Auto12Ball_Back_Sorted extends LinearOpMode {
// Robot robot;
//import java.util.List; MultipleTelemetry TELE;
// Follower follower;
//@Config MeasuringLoopTimes loopTimes;
//@Autonomous (preselectTeleOp = "TeleopV4")
//public class Auto12Ball_Back_Sorted extends LinearOpMode { // Wait Times
// Robot robot; public static double shootTime = 2;
// MultipleTelemetry TELE; public static double openGateTime = 1.5;
// // Flywheel flywheel;
//// Targeting targeting; // Extra Variables
//// Targeting.Settings targetingSettings; public static double intakePower = 0.3;
// Follower follower; double shootX, shootY, shootH;
// // Turret turret;
//// Spindexer spindexer; // Initialize path state machine
//// Servos servos; private enum PathState {
// MeasuringLoopTimes loopTimes; PUSHBOT, DRIVE_SHOOT0, WAIT_SHOOT0,
// PICKUP1, DRIVE_OPENGATE, OPENGATE, DRIVE_SHOOT1, WAIT_SHOOT1,
// // Wait Times DRIVE_PICKUP2, PICKUP2, DRIVE_SHOOT2, WAIT_SHOOT2,
// public static double shootTime = 2; DRIVE_PICKUP3, PICKUP3, DRIVE_SHOOT3, WAIT_SHOOT3
// }
// // Extra Variables PathState pathState = PathState.PUSHBOT;
// public static double intakePower = 0.3;
// double shootX, shootY, shootH; // Poses
// public static double startPoseX = 84, startPoseY = 7, startPoseH = 90;
// // Initialize path state machine public static double pushBotX = 94, pushBotY = 9, pushBotH = 100;
// private enum PathState { public static double shoot0ControlX = 88.29667812142038, shoot0ControlY = 52.03493699885454;
// PUSHBOT, DRIVE_SHOOT0, WAIT_SHOOT0, public static double shoot0X = 91, shoot0Y = 80, shoot0H = 0;
// PICKUP1, OPENGATE, DRIVE_SHOOT1, WAIT_SHOOT1, public static double pickup1ControlX = 109.29381443298968, pickup1ControlY = 82.70618556701031;
// DRIVE_PICKUP2, PICKUP2, DRIVE_SHOOT2, WAIT_SHOOT2, public static double pickup1X = 126, pickup1Y = 82, pickup1H = 0;
// DRIVE_PICKUP3, PICKUP3, DRIVE_SHOOT3, WAIT_SHOOT3 public static double openGateControlX = 109.184421534937, openGateControlY = 74.24455899198165;
// } public static double openGateX = 129, openGateY = 74, openGateH = 0;
// PathState pathState = PathState.DRIVE_SHOOT0; public static double shoot1ControlX = 112, shoot1ControlY = 75;
// public static double shoot1X = 91, shoot1Y = 80, shoot1H = -12;
// // Poses public static double drivePickup2X = 102, drivePickup2Y = 58.5, drivePickup2H = 0;
// public static double startPoseX = 84, startPoseY = 7, startPoseH = 90; public static double pickup2X = 133, pickup2Y = 57, pickup2H = 0;
// public static double pushBotX = 94, pushBotY = 9, pushBotH = 100; public static double shoot2ControlX = 102, shoot2ControlY = 63;
// public static double shoot0X = 91, shoot0Y = 80, shoot0H = 0; public static double shoot2X = 91, shoot2Y = 80, shoot2H = -50;
// public static double pickup1X = 126, pickup1Y = 82, pickup1H = 0; public static double drivePickup3X = 102, drivePickup3Y = 34.5, drivePickup3H = 0;
// public static double openGateControlX = 109.184421534937, openGateControlY = 74.24455899198165; public static double pickup3X = 133, pickup3Y = 34.5, pickup3H = 0;
// public static double openGateX = 129, openGateY = 74, openGateH = 0; public static double shoot3ControlX = 97.62371134020621, shoot3ControlY = 34.813287514318446;
// public static double shoot1ControlX = 112, shoot1ControlY = 75; public static double shoot3X = 84, shoot3Y = 105, shoot3H = -80;
// public static double shoot1X = 91, shoot1Y = 80, shoot1H = -12; Pose startPose, pushBot, shoot0Control, shoot0,
// public static double drivePickup2X = 102, drivePickup2Y = 58.5, drivePickup2H = 0; pickup1Control, pickup1, openGateControl, openGate, shoot1Control, shoot1,
// public static double pickup2X = 133, pickup2Y = 57, pickup2H = 0; drivePickup2, pickup2, shoot2Control, shoot2,
// public static double shoot2ControlX = 102, shoot2ControlY = 63; drivePickup3, pickup3, shoot3Control, shoot3;
// public static double shoot2X = 91, shoot2Y = 80, shoot2H = -50; private void initializePoses(){
// public static double drivePickup3X = 102, drivePickup3Y = 34.5, drivePickup3H = 0; startPose = new Pose(startPoseX, startPoseY, Math.toRadians(startPoseH));
// public static double pickup3X = 133, pickup3Y = 34.5, pickup3H = 0; pushBot = new Pose(pushBotX, pushBotY, Math.toRadians(pushBotH));
// public static double shoot3ControlX = 97.62371134020621, shoot3ControlY = 34.813287514318446; shoot0Control = new Pose(shoot0ControlX, shoot0ControlY);
// public static double shoot3X = 84, shoot3Y = 105, shoot3H = -80; shoot0 = new Pose(shoot0X, shoot0Y, Math.toRadians(shoot0H));
// Pose startPose, pushBot, shoot0, pickup1Control = new Pose(pickup1ControlX, pickup1ControlY);
// pickup1, openGateControl, openGate, shoot1Control, shoot1, pickup1 = new Pose(pickup1X, pickup1Y, Math.toRadians(pickup1H));
// drivePickup2, pickup2, shoot2Control, shoot2, openGateControl = new Pose(openGateControlX, openGateControlY);
// drivePickup3, pickup3, shoot3Control, shoot3; openGate = new Pose(openGateX, openGateY, Math.toRadians(openGateH));
// private void initializePoses(){ shoot1Control = new Pose(shoot1ControlX, shoot1ControlY);
// startPose = new Pose(startPoseX, startPoseY, Math.toRadians(startPoseH)); shoot1 = new Pose(shoot1X, shoot1Y, Math.toRadians(shoot1H));
// pushBot = new Pose(pushBotX, pushBotY, Math.toRadians(pushBotH)); drivePickup2 = new Pose(drivePickup2X, drivePickup2Y, Math.toRadians(drivePickup2H));
// shoot0 = new Pose(shoot0X, shoot0Y, Math.toRadians(shoot0H)); pickup2 = new Pose(pickup2X, pickup2Y, Math.toRadians(pickup2H));
// pickup1 = new Pose(pickup1X, pickup1Y, Math.toRadians(pickup1H)); shoot2Control = new Pose(shoot2ControlX, shoot2ControlY);
// openGateControl = new Pose(openGateControlX, openGateControlY); shoot2 = new Pose(shoot2X, shoot2Y, Math.toRadians(shoot2H));
// openGate = new Pose(openGateX, openGateY, Math.toRadians(openGateH)); drivePickup3 = new Pose(drivePickup3X, drivePickup3Y, Math.toRadians(drivePickup3H));
// shoot1Control = new Pose(shoot1ControlX, shoot1ControlY); pickup3 = new Pose(pickup3X, pickup3Y, Math.toRadians(pickup3H));
// shoot1 = new Pose(shoot1X, shoot1Y, Math.toRadians(shoot1H)); shoot3Control = new Pose(shoot3ControlX, shoot3ControlY);
// drivePickup2 = new Pose(drivePickup2X, drivePickup2Y, Math.toRadians(drivePickup2H)); shoot3 = new Pose(shoot3X, shoot3Y, Math.toRadians(shoot3H));
// pickup2 = new Pose(pickup2X, pickup2Y, Math.toRadians(pickup2H)); }
// shoot2Control = new Pose(shoot2ControlX, shoot2ControlY);
// shoot2 = new Pose(shoot2X, shoot2Y, Math.toRadians(shoot2H)); //Building Paths
// drivePickup3 = new Pose(drivePickup3X, drivePickup3Y, Math.toRadians(drivePickup3H)); PathChain startPose_pushBot, pushBot_shoot0,
// pickup3 = new Pose(pickup3X, pickup3Y, Math.toRadians(pickup3H)); shoot0_pickup1, pickup1_openGate, openGate_shoot1,
// shoot3Control = new Pose(shoot3ControlX, shoot3ControlY); shoot1_drivePickup2, drivePickup2_pickup2, pickup2_shoot2,
// shoot3 = new Pose(shoot3X, shoot3Y, Math.toRadians(shoot3H)); shoot2_drivePickup3, drivePickup3_pickup3, pickup3_shoot3;
// } private void buildPaths(){
// startPose_pushBot = follower.pathBuilder()
// //Building Paths .addPath(new BezierLine(startPose, pushBot))
// PathChain startPose_pushBot, pushBot_shoot0, .setLinearHeadingInterpolation(startPose.getHeading(), pushBot.getHeading())
// shoot0_pickup1, pickup1_openGate, openGate_shoot1, .build();
// shoot1_drivePickup2, drivePickup2_pickup2, pickup2_shoot2,
// shoot2_drivePickup3, drivePickup3_pickup3, pickup3_shoot3; pushBot_shoot0 = follower.pathBuilder()
// private void buildPaths(){ .addPath(new BezierCurve(pushBot, shoot0Control, shoot0))
// startPose_pushBot = follower.pathBuilder() .setLinearHeadingInterpolation(pushBot.getHeading(), shoot0.getHeading())
// .addPath(new BezierLine(startPose, pushBot)) .build();
// .setLinearHeadingInterpolation(startPose.getHeading(), pushBot.getHeading())
// .build(); shoot0_pickup1 = follower.pathBuilder()
// } .addPath(new BezierCurve(shoot0, pickup1Control, pickup1))
// .setLinearHeadingInterpolation(shoot0.getHeading(), pickup1.getHeading())
// //Path State Machine .build();
// private boolean startAuto = true;
// private double timeStamp = 0; pickup1_openGate = follower.pathBuilder()
// private void pathStateMachine(){ .addPath(new BezierCurve(pickup1, openGateControl, openGate))
// double currentTime = (double) System.currentTimeMillis() / 1000; .setLinearHeadingInterpolation(pickup1.getHeading(), openGate.getHeading())
// switch(pathState){ .build();
// case DRIVE_SHOOT0:
// if (startAuto){ openGate_shoot1 = follower.pathBuilder()
// follower.followPath(startPose_shoot0, true); .addPath(new BezierCurve(openGate, shoot1Control, shoot1))
// startAuto = false; .setLinearHeadingInterpolation(openGate.getHeading(), shoot1.getHeading())
// shootX = shoot0X; .build();
// shootY = shoot0Y;
// shootH = shoot0H; shoot1_drivePickup2 = follower.pathBuilder()
// } .addPath(new BezierLine(shoot1, drivePickup2))
// driveShoot(PathState.WAIT_SHOOT0, currentTime); .setLinearHeadingInterpolation(shoot1.getHeading(), drivePickup2.getHeading())
// break; .build();
// case WAIT_SHOOT0:
// waitShoot(PathState.DRIVE_PICKUP1, shoot0_drivePickup1, currentTime); drivePickup2_pickup2 = follower.pathBuilder()
// break; .addPath(new BezierLine(drivePickup2, pickup2))
// case DRIVE_PICKUP1: .setLinearHeadingInterpolation(drivePickup2.getHeading(), pickup2.getHeading())
// drivePickup(PathState.PICKUP1, drivePickup1_pickup1); .build();
// break;
// case PICKUP1: pickup2_shoot2 = follower.pathBuilder()
// pickup(PathState.DRIVE_SHOOT1, pickup1_shoot1); .addPath(new BezierCurve(pickup2, shoot2Control, shoot2))
// shootX = shoot1X; .setLinearHeadingInterpolation(pickup2.getHeading(), shoot2.getHeading())
// shootY = shoot1Y; .build();
// shootH = shoot1H;
// break; shoot2_drivePickup3 = follower.pathBuilder()
// case DRIVE_SHOOT1: .addPath(new BezierLine(shoot2, drivePickup3))
// intakePowerDown(timeStamp, currentTime); .setLinearHeadingInterpolation(shoot2.getHeading(), drivePickup3.getHeading())
// driveShoot(PathState.WAIT_SHOOT1, currentTime); .build();
// break;
// case WAIT_SHOOT1: drivePickup3_pickup3 = follower.pathBuilder()
// waitShoot(PathState.DRIVE_PICKUP2, shoot1_drivePickup2, currentTime); .addPath(new BezierLine(drivePickup3, pickup3))
// break; .setLinearHeadingInterpolation(drivePickup3.getHeading(), pickup3.getHeading())
// case DRIVE_PICKUP2: .build();
// drivePickup(PathState.PICKUP2, drivePickup2_pickup2);
// break; pickup3_shoot3 = follower.pathBuilder()
// case PICKUP2: .addPath(new BezierCurve(pickup3, shoot3Control, shoot3))
// pickup(PathState.DRIVE_SHOOT2, pickup2_shoot2); .setLinearHeadingInterpolation(pickup3.getHeading(), shoot3.getHeading())
// shootX = shoot2X; .build();
// shootY = shoot2Y; }
// shootH = shoot2H;
// break; //Path State Machine
// case DRIVE_SHOOT2: private boolean startAuto = true;
// intakePowerDown(timeStamp, currentTime); private double timeStamp = 0;
// driveShoot(PathState.WAIT_SHOOT2, currentTime); private void pathStateMachine(){
// break; double currentTime = (double) System.currentTimeMillis() / 1000;
// case WAIT_SHOOT2: switch(pathState){
// waitShoot(PathState.DRIVE_PICKUP3, shoot2_drivePickup3, currentTime); case PUSHBOT:
// break; if (startAuto){
// case DRIVE_PICKUP3: follower.followPath(startPose_pushBot, true);
// drivePickup(PathState.PICKUP3, drivePickup3_pickup3); startAuto = false;
// break; shootX = shoot0X;
// case PICKUP3: shootY = shoot0Y;
// pickup(PathState.DRIVE_SHOOT3, pickup3_shoot3); shootH = shoot0H;
// shootX = shoot3X; }
// shootY = shoot3Y; if (!follower.isBusy()){
// shootH = shoot3H; follower.followPath(pushBot_shoot0, true);
// break; pathState = PathState.DRIVE_SHOOT0;
// case DRIVE_SHOOT3: }
// intakePowerDown(timeStamp, currentTime); break;
// driveShoot(PathState.WAIT_SHOOT3, currentTime); case DRIVE_SHOOT0:
// break; if (!follower.isBusy()){
// case WAIT_SHOOT3: timeStamp = currentTime;
//// if (spindexer.shootAllComplete()){ pathState = PathState.WAIT_SHOOT0;
//// spindexer.resetSpindexer(); }
//// TELE.addLine("Done Auto"); break;
//// } case WAIT_SHOOT0:
// break; if (currentTime - timeStamp > shootTime){
// default: follower.followPath(shoot0_pickup1, intakePower, false);
// break; pathState = PathState.PICKUP1;
// } }
// TELE.update(); // use for debugging break;
// } case PICKUP1:
// if (!follower.isBusy()){
// // Voids for State Machine follower.followPath(pickup1_openGate, true);
// private void intakePowerDown(double stamp, double currentTime) { pathState = PathState.OPENGATE;
// double pow = (stamp - currentTime) / 2; // adjust denominator to see how much time to adjust shootX = shoot1X;
// if (pow < -1) {pow = 0;} shootY = shoot1Y;
//// spindexer.setIntakePower(pow); shootH = shoot1H;
// } }
// private void driveShoot(PathState nextState, double currentTime){ break;
// if (!follower.isBusy()){ case DRIVE_OPENGATE:
// pathState = nextState; if (!follower.isBusy()){
// timeStamp = currentTime; pathState = PathState.OPENGATE;
//// spindexer.prepareShootAllContinous(); timeStamp = currentTime;
// } }
// } break;
// private void waitShoot(PathState nextState, PathChain nextPath, double currentTime) { case OPENGATE:
// if (currentTime - timeStamp > shootTime) { // spindexer.shootAllComplete() || if (currentTime - timeStamp > openGateTime){
//// spindexer.resetSpindexer(); follower.followPath(openGate_shoot1, true);
// pathState = nextState; pathState = PathState.DRIVE_SHOOT1;
// follower.followPath(nextPath, true); }
//// spindexer.setIntakePower(1); break;
// } case DRIVE_SHOOT1:
// } if (!follower.isBusy()){
// private void drivePickup(PathState nextState, PathChain nextPath) { pathState = PathState.WAIT_SHOOT1;
// if (!follower.isBusy()) { timeStamp = currentTime;
// pathState = nextState; }
// follower.followPath(nextPath, intakePower, false); break;
// } case WAIT_SHOOT1:
// } if (currentTime - timeStamp > shootTime){
// private void pickup(PathState nextState, PathChain nextPath) { follower.followPath(shoot1_drivePickup2, true);
// if (!follower.isBusy()) { pathState = PathState.DRIVE_PICKUP2;
// pathState = nextState; }
// follower.followPath(nextPath, true); break;
// } case DRIVE_PICKUP2:
// } if (!follower.isBusy()) {
// follower.followPath(drivePickup2_pickup2, intakePower, false);
// // Used for changing alliance pathState = PathState.PICKUP2;
// private double adjustXPoseBasedOnAlliance(double pose) {return (144-pose);} }
// private double adjustHeadingBasedOnAlliance(double heading){ break;
// heading = 180 - heading; case PICKUP2:
// while (heading > 180) {heading-=360;} if (!follower.isBusy()){
// while (heading <= -180) {heading+=360;} follower.followPath(pickup2_shoot2, true);
// return heading; pathState = PathState.DRIVE_SHOOT2;
// } }
// shootX = shoot2X;
// @Override shootY = shoot2Y;
// public void runOpMode() throws InterruptedException { shootH = shoot2H;
// Robot.resetInstance(); break;
// robot = Robot.getInstance(hardwareMap); case DRIVE_SHOOT2:
// List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class); if (!follower.isBusy()){
// for (LynxModule hub : allHubs) { pathState = PathState.WAIT_SHOOT2;
// hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL); timeStamp = currentTime;
// } }
// TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry()); break;
//// flywheel = new Flywheel(hardwareMap); case WAIT_SHOOT2:
//// targeting = new Targeting(); if (currentTime - timeStamp > shootTime){
//// targetingSettings = new Targeting.Settings(0,0); follower.followPath(shoot2_drivePickup3, true);
// follower = Constants.createFollower(hardwareMap); pathState = PathState.DRIVE_PICKUP3;
// follower.setStartingPose(new Pose(72,72,0)); }
//// turret = new Turret(robot, TELE, robot.limelight); break;
//// spindexer = new Spindexer(hardwareMap); case DRIVE_PICKUP3:
//// servos = new Servos(hardwareMap); if (!follower.isBusy()){
// loopTimes = new MeasuringLoopTimes(); follower.followPath(drivePickup3_pickup3, intakePower, false);
// loopTimes.init(); pathState = PathState.PICKUP3;
// }
//// robot.light.setPosition(Color.LightRed); break;
// case PICKUP3:
// boolean initializeRobot = false; if (!follower.isBusy()){
// while (opModeInInit()){ follower.followPath(pickup3_shoot3, true);
// follower.update(); pathState = PathState.DRIVE_SHOOT3;
// }
// if (gamepad1.crossWasPressed() && !initializeRobot){ shootX = shoot3X;
// Color.redAlliance = !Color.redAlliance; shootY = shoot3Y;
//// if (Color.redAlliance){ shootH = shoot3H;
//// robot.light.setPosition(Color.LightRed); break;
//// } else { case DRIVE_SHOOT3:
//// robot.light.setPosition(Color.LightBlue); if (!follower.isBusy()){
//// } pathState = PathState.WAIT_SHOOT3;
// }
//// double[] xPoses = {startPoseX, shoot0X, break;
//// drivePickup1X, pickup1X, shoot1X, case WAIT_SHOOT3:
//// drivePickup2ControlX, drivePickup2X, pickup2X, shoot2ControlX, shoot2X, // add line here to say "done auto'
//// drivePickup3ControlX, drivePickup3X, pickup3X, shoot3ControlX, shoot3X}; break;
//// default:
//// double[] headings = {startPoseH, shoot0H, break;
//// drivePickup1H, pickup1H, shoot1H, }
//// drivePickup2H, pickup2H, shoot2H, TELE.update(); // use for debugging
//// drivePickup3H, pickup3H, shoot3H}; }
//
//// for (int i = 0; i < xPoses.length; i++) {xPoses[i] = adjustXPoseBasedOnAlliance(xPoses[i]);} // Used for changing alliance
//// for (int i = 0; i < headings.length; i++) {headings[i] = adjustHeadingBasedOnAlliance(headings[i]);} private double adjustXPoseBasedOnAlliance(double pose) {return (144-pose);}
// } private double adjustHeadingBasedOnAlliance(double heading){
// heading = 180 - heading;
// if (gamepad1.triangleWasPressed()){ while (heading > 180) {heading-=360;}
// initializeRobot = true; while (heading <= -180) {heading+=360;}
// initializePoses(); return heading;
// follower.setPose(startPose); }
// buildPaths();
// sleep(2000); @Override
// public void runOpMode() throws InterruptedException {
//// turret.setTurret(turrDefault); Robot.resetInstance();
//// servos.setSpinPos(spinStartPos); robot = Robot.getInstance(hardwareMap);
// } List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
// for (LynxModule hub : allHubs) {
// TELE.addData("Red Alliance?", Color.redAlliance); hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
// TELE.addData("Initialized Robot? (Don't change this until alliance is selected)", initializeRobot); }
// TELE.addData("Start Pose", follower.getPose()); TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
// TELE.update(); follower = Constants.createFollower(hardwareMap);
// } follower.setStartingPose(new Pose(72,72,0));
// loopTimes = new MeasuringLoopTimes();
// waitForStart(); loopTimes.init();
//
// if (isStopRequested()) return; boolean initializeRobot = false;
// while (opModeInInit()){
//// robot.transfer.setPower(1); follower.update();
// limelightUsed = false;
// if (gamepad1.crossWasPressed() && !initializeRobot){
// while (opModeIsActive()){ Color.redAlliance = !Color.redAlliance;
// follower.update();
// pathStateMachine(); double[] xPoses = {startPoseX, pushBotX, shoot0ControlX, shoot0X,
// Pose currentPose = follower.getPose(); pickup1ControlX, pickup1X, openGateControlX, openGateX, shoot1ControlX, shoot1X,
//// teleStartPoseX = currentPose.getX(); drivePickup2X, pickup2X, shoot2ControlX, shoot2X,
//// teleStartPoseY = currentPose.getY(); drivePickup3X, pickup3X, shoot3ControlX, shoot3X};
//// teleStartPoseH = Math.toDegrees(currentPose.getHeading());
//// double[] headings = {startPoseH, pushBotH, shoot0H,
//// turret.trackGoal(new Pose(shootX, shootY, Math.toRadians(shootH))); pickup1H, openGateH, shoot1H,
//// targetingSettings = targeting.calculateSettings(shootX, shootY, Math.toRadians(shootH), 0, turretInterpolate); drivePickup2H, pickup2H, shoot2H,
//// drivePickup3H, pickup3H, shoot3H};
//// double voltage = robot.voltage.getVoltage();
//// flywheel.setPIDF(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F / voltage); for (int i = 0; i < xPoses.length; i++) {xPoses[i] = adjustXPoseBasedOnAlliance(xPoses[i]);}
//// flywheel.manageFlywheel(targetingSettings.flywheelRPM); for (int i = 0; i < headings.length; i++) {headings[i] = adjustHeadingBasedOnAlliance(headings[i]);}
//// servos.setHoodPos(targetingSettings.hoodAngle); }
////
//// if (driveToShoot()){servos.setSpinPos(spinStartPos);} if (gamepad1.triangleWasPressed()){
//// else {spindexer.processIntake();} initializeRobot = true;
// initializePoses();
// for (LynxModule hub : allHubs) { follower.setPose(startPose);
// hub.clearBulkCache(); buildPaths();
// } sleep(2000);
// loopTimes.loop(); }
//
// TELE.addData("Avg Loop Time", loopTimes.getAvgLoopTime()); TELE.addData("Red Alliance?", Color.redAlliance);
// TELE.addData("Min Loop Time", loopTimes.getMinLoopTimeOneMin()); TELE.addData("Initialized Robot? (Don't change this until alliance is selected)", initializeRobot);
// TELE.addData("Max Loop Time", loopTimes.getMaxLoopTimeOneMin()); TELE.addData("Start Pose", follower.getPose());
// TELE.addData("X:", currentPose.getX()); TELE.update();
// TELE.addData("Y:", currentPose.getY()); }
// TELE.addData("H:", currentPose.getHeading());
// TELE.update(); waitForStart();
// }
// } if (isStopRequested()) return;
//}
limelightUsed = false;
while (opModeIsActive()){
follower.update();
pathStateMachine();
Pose currentPose = follower.getPose();
teleStartPoseX = currentPose.getX();
teleStartPoseY = currentPose.getY();
teleStartPoseH = Math.toDegrees(currentPose.getHeading());
for (LynxModule hub : allHubs) {
hub.clearBulkCache();
}
loopTimes.loop();
TELE.addData("Avg Loop Time", loopTimes.getAvgLoopTime());
TELE.addData("Min Loop Time", loopTimes.getMinLoopTimeOneMin());
TELE.addData("Max Loop Time", loopTimes.getMaxLoopTimeOneMin());
TELE.addData("X:", currentPose.getX());
TELE.addData("Y:", currentPose.getY());
TELE.addData("H:", currentPose.getHeading());
TELE.update();
}
}
}

View File

@@ -25,6 +25,8 @@ public class TeleopV4 extends LinearOpMode {
MultipleTelemetry TELE; MultipleTelemetry TELE;
Follower follower; Follower follower;
SpindexerTransferIntake spindexerTransferIntake; SpindexerTransferIntake spindexerTransferIntake;
Turret turret;
Flywheel flywheel;
@Override @Override
public void runOpMode() throws InterruptedException { public void runOpMode() throws InterruptedException {
@@ -40,7 +42,11 @@ public class TeleopV4 extends LinearOpMode {
Pose start = new Pose(teleStartPoseX, teleStartPoseY, Math.toRadians(teleStartPoseH)); Pose start = new Pose(teleStartPoseX, teleStartPoseY, Math.toRadians(teleStartPoseH));
follower.setStartingPose(start); follower.setStartingPose(start);
shooter = new Shooter(robot, TELE, follower, Color.redAlliance); flywheel = new Flywheel(robot);
turret = new Turret(robot);
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel);
shooter.setState(Shooter.ShooterState.TRACK_GOAL); shooter.setState(Shooter.ShooterState.TRACK_GOAL);
spindexerTransferIntake = new SpindexerTransferIntake(robot, TELE); spindexerTransferIntake = new SpindexerTransferIntake(robot, TELE);
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID); spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);

View File

@@ -124,7 +124,8 @@ public class Hardware_Tester extends LinearOpMode {
// Sensor Data // Sensor Data
// TELE.addData("Beam Break 1?", robot.beam1.isPressed()); TELE.addData("Beam Break insideBeam?", robot.insideBeam.isPressed());
TELE.addData("Beam Break outsideBeam?", robot.outsideBeam.isPressed());
// TELE.addData("Beam Break 2?", robot.beam2.isPressed()); // TELE.addData("Beam Break 2?", robot.beam2.isPressed());
// TELE.addData("Beam Break 3?", robot.beam3.isPressed()); // TELE.addData("Beam Break 3?", robot.beam3.isPressed());

View File

@@ -11,25 +11,26 @@ import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.utilsv2.Flywheel; import org.firstinspires.ftc.teamcode.utilsv2.Flywheel;
import org.firstinspires.ftc.teamcode.utilsv2.Robot; import org.firstinspires.ftc.teamcode.utilsv2.Robot;
import org.firstinspires.ftc.teamcode.utilsv2.Shooter; import org.firstinspires.ftc.teamcode.utilsv2.Shooter;
import org.firstinspires.ftc.teamcode.utilsv2.Turret;
@Config @Config
@TeleOp @TeleOp
public class NewShooterTest extends LinearOpMode { public class NewShooterTest extends LinearOpMode {
Robot robot; Robot robot;
Flywheel flywheel;
Turret turret;
MultipleTelemetry TELE; MultipleTelemetry TELE;
Flywheel rpmFlywheel;
public static boolean intake = true; public static boolean intake = true;
public static boolean shoot = false; public static boolean shoot = false;
public static double intakePower = 1.0; public static double intakePower = 1.0;
public static double transferShootPower = -1; public static double transferShootPower = -1;
public static double transferIntakePower = -1.0; public static double transferIntakePower = -1;
public static double turretPos = 0.51; public static double turretPos = 0.51;
public static double hoodPos = 0.51; public static double hoodPos = 0.51;
public static double flywheel = 0; public static double flywheel_velo = 0;
public static double shooterP = 255, shooterI = 0, shooterD = 0, shooterF = 75; public static double shooterP = 255, shooterI = 0, shooterD = 0, shooterF = 75;
@@ -45,22 +46,25 @@ public class NewShooterTest extends LinearOpMode {
@Override @Override
public void runOpMode() throws InterruptedException { public void runOpMode() throws InterruptedException {
Robot.resetInstance();
robot = Robot.getInstance(hardwareMap); robot = Robot.getInstance(hardwareMap);
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry()); TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
flywheel = new Flywheel(robot);
turret = new Turret(robot);
Shooter shooter = new Shooter( Shooter shooter = new Shooter(
robot, robot,
new MultipleTelemetry( TELE,
telemetry,
FtcDashboard.getInstance().getTelemetry()
),
Constants.createFollower(hardwareMap), Constants.createFollower(hardwareMap),
true true,
turret,
flywheel
); );
rpmFlywheel = new Flywheel(robot);
shooter.setState(Shooter.ShooterState.MANUAL); shooter.setState(Shooter.ShooterState.MANUAL);
waitForStart(); waitForStart();
@@ -71,9 +75,9 @@ public class NewShooterTest extends LinearOpMode {
robot.setHoodPos(hoodPos); robot.setHoodPos(hoodPos);
shooter.setTurretPosition(turretPos); shooter.setTurretPosition(turretPos);
shooter.setFlywheelVelocity(flywheel); shooter.setFlywheelVelocity(flywheel_velo);
double voltage = robot.voltage.getVoltage(); double voltage = robot.voltage.getVoltage();
rpmFlywheel.setPIDF(shooterP, shooterI, shooterD, shooterF / voltage); flywheel.setPIDF(shooterP, shooterI, shooterD, shooterF / voltage);
robot.setSpinPos(ServoPositions.spindexer_A2); robot.setSpinPos(ServoPositions.spindexer_A2);
@@ -130,7 +134,11 @@ public class NewShooterTest extends LinearOpMode {
} }
} }
TELE.addData("Flywheel Velocity", (robot.shooter1.getVelocity() * 60) / 28); TELE.addData("Flywheel Velocity1", (robot.shooter1.getVelocity() * 60) / 28);
TELE.addData("Flywheel Velocity2", (robot.shooter2.getVelocity() * 60) / 28);
TELE.addData("Flywheel Averag Velocity", flywheel.getAverageVelocity());
TELE.addData("PIDF Coefficients", Flywheel.shooterPIDF);
TELE.addData("Power", flywheel.getShooterPower());
TELE.update(); TELE.update();
shooter.update(); shooter.update();

View File

@@ -5,12 +5,19 @@ import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.HardwareMap; import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.PIDFCoefficients; import com.qualcomm.robotcore.hardware.PIDFCoefficients;
import org.firstinspires.ftc.teamcode.utilsv2.Robot;
import java.util.LinkedList; import java.util.LinkedList;
public class Flywheel { public class Flywheel {
Robot robot; Robot robot;
public PIDFCoefficients shooterPIDF1, shooterPIDF2; // public PIDFCoefficients shooterPIDF1, shooterPIDF2;
public static PIDFCoefficients shooterPIDF;
public static double shooterPIDF_P = 255;
public static double shooterPIDF_I = 0.0;
public static double shooterPIDF_D = 0.0;
public static double shooterPIDF_F = 75;
private double velo = 0.0; private double velo = 0.0;
private double velo1 = 0.0; private double velo1 = 0.0;
@@ -26,7 +33,7 @@ public class Flywheel {
public Flywheel(Robot rob) { public Flywheel(Robot rob) {
robot = rob; robot = rob;
shooterPIDF1 = new PIDFCoefficients(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F / 12); shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / 12);
} }
public double getVelo() { public double getVelo() {
@@ -50,25 +57,26 @@ public class Flywheel {
} }
// Set the robot PIDF for the next cycle. // Set the robot PIDF for the next cycle.
private double prevF = 0;
public static double voltagePIDFDifference = 0.8;
public void setPIDF(double p, double i, double d, double f) { public void setPIDF(double p, double i, double d, double f) {
shooterPIDF1.p = p; shooterPIDF.p = p;
shooterPIDF1.i = i; shooterPIDF.i = i;
shooterPIDF1.d = d; shooterPIDF.d = d;
shooterPIDF1.f = f; shooterPIDF.f = f;
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1); robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
}
// if (Math.abs(prevF - f) > voltagePIDFDifference) { private double prevF = 0;
//
// robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1); public static double voltagePIDFDifference = 0.8;
// public void setF(double f){
// prevF = f; if (Math.abs(prevF - f) > voltagePIDFDifference) {
// } shooterPIDF.f = f;
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
prevF = f;
}
} }
// Convert from RPM to Ticks per Second // Convert from RPM to Ticks per Second
@@ -99,6 +107,7 @@ public class Flywheel {
averageVelocity = sum / velocityHistory.size(); averageVelocity = sum / velocityHistory.size();
} }
double power;
public void manageFlywheel(double commandedVelocity) { public void manageFlywheel(double commandedVelocity) {
if (Math.abs(targetVelocity - commandedVelocity) > 0.0001) { if (Math.abs(targetVelocity - commandedVelocity) > 0.0001) {
@@ -106,7 +115,7 @@ public class Flywheel {
} }
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity)); robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
double power = robot.shooter1.getPower(); power = robot.shooter1.getPower();
robot.shooter2.setPower(power); robot.shooter2.setPower(power);
velo1 = TPS_to_RPM(robot.shooter1.getVelocity()); velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
@@ -119,4 +128,5 @@ public class Flywheel {
steady = (Math.abs(commandedVelocity - averageVelocity) < 50); steady = (Math.abs(commandedVelocity - averageVelocity) < 50);
} }
public double getShooterPower(){return power;}
} }

View File

@@ -1,5 +1,7 @@
package org.firstinspires.ftc.teamcode.utilsv2; package org.firstinspires.ftc.teamcode.utilsv2;
import android.view.View;
import com.qualcomm.hardware.limelightvision.Limelight3A; import com.qualcomm.hardware.limelightvision.Limelight3A;
import com.qualcomm.hardware.rev.RevColorSensorV3; import com.qualcomm.hardware.rev.RevColorSensorV3;
import com.qualcomm.robotcore.hardware.AnalogInput; import com.qualcomm.robotcore.hardware.AnalogInput;
@@ -19,6 +21,7 @@ public class Robot {
// Singleton instance // Singleton instance
private static Robot instance; private static Robot instance;
/** /**
* Returns the existing Robot instance or creates one if it doesn't exist. * Returns the existing Robot instance or creates one if it doesn't exist.
*/ */
@@ -45,11 +48,6 @@ public class Robot {
public DcMotorEx backRight; public DcMotorEx backRight;
public DcMotorEx intake; public DcMotorEx intake;
public DcMotorEx transfer; public DcMotorEx transfer;
public PIDFCoefficients shooterPIDF;
public static double shooterPIDF_P = 255;
public static double shooterPIDF_I = 0.0;
public static double shooterPIDF_D = 0.0;
public static double shooterPIDF_F = 75;
// public double[] shooterPIDF_StepSizes = {10.0, 1.0, 0.001, 0.0001}; // public double[] shooterPIDF_StepSizes = {10.0, 1.0, 0.001, 0.0001};
public DcMotorEx shooter1; public DcMotorEx shooter1;
public DcMotorEx shooter2; public DcMotorEx shooter2;
@@ -65,7 +63,6 @@ public class Robot {
public Servo spin2; public Servo spin2;
public TouchSensor insideBeam; public TouchSensor insideBeam;
public TouchSensor outsideBeam; public TouchSensor outsideBeam;
public RevColorSensorV3 revSensor; public RevColorSensorV3 revSensor;
public VoltageSensor voltage; public VoltageSensor voltage;
@@ -106,10 +103,9 @@ public class Robot {
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2"); shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
shooter1.setDirection(DcMotorSimple.Direction.REVERSE); shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / 12); // shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / 12);
shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER); shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF); // shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
shooter1.setVelocity(0);
shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER); shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
hood = hardwareMap.get(Servo.class, "hood"); hood = hardwareMap.get(Servo.class, "hood");

View File

@@ -21,16 +21,21 @@ public class Shooter {
Follower follow; Follower follow;
public Shooter(Robot rob, MultipleTelemetry TELE, Follower follower, boolean redAlliance) { public Shooter(Robot rob, MultipleTelemetry TELE, Follower follower, boolean redAlliance, Turret turret, Flywheel flywheel) {
this.robot = rob; this.robot = rob;
this.fly = new Flywheel(rob); this.fly = flywheel;
this.turr = new Turret(rob); this.turr = turret;
this.follow = follower; this.follow = follower;
this.commander = new VelocityCommander(); this.commander = new VelocityCommander();
setRedAlliance(redAlliance); setRedAlliance(redAlliance);
if (redAlliance) { }
public void setRedAlliance(boolean input) {
this.red = input;
if (this.red) {
goalX = 144; goalX = 144;
} else { } else {
goalX = 0; goalX = 0;
@@ -38,10 +43,6 @@ public class Shooter {
goalY = 144; goalY = 144;
} }
public void setRedAlliance(boolean input) {
this.red = input;
}
private double flywheelVelocity = 0.0; private double flywheelVelocity = 0.0;
private double turretPosition = 0.5; private double turretPosition = 0.5;