4 Commits

Author SHA1 Message Date
855dac7122 teleop tweaks 2026-06-07 23:48:26 -05:00
4cd890cef8 gate cycle auto good 2026-06-07 23:24:35 -05:00
9d03e1125a a lot of stuff happened 2026-06-07 21:19:00 -05:00
104058bbce copied changes from Mr. Kruger's commit 2026-06-07 15:06:54 -05:00
12 changed files with 325 additions and 168 deletions

View File

@@ -390,6 +390,9 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
if (isStopRequested()) return; if (isStopRequested()) return;
while (opModeIsActive()){ while (opModeIsActive()){
robot.setRapidFireBlockerPos(ServoPositions.rapidFireBlocker_Closed);
park.unpark();
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR); shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
shooter.update(robot.voltage.getVoltage()); shooter.update(robot.voltage.getVoltage());

View File

@@ -283,6 +283,10 @@ public class Auto15Ball_Back extends LinearOpMode {
boolean initializeRobot = false; boolean initializeRobot = false;
while (opModeInInit()){ while (opModeInInit()){
park.unpark();
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
follower.update(); follower.update();
if (gamepad1.squareWasPressed()){ if (gamepad1.squareWasPressed()){

View File

@@ -35,13 +35,16 @@ public class Auto21Ball_Front_Gate extends LinearOpMode {
Flywheel flywheel; Flywheel flywheel;
VelocityCommander commander; VelocityCommander commander;
SpindexerTransferIntake spindexer; SpindexerTransferIntake spindexer;
double runtime = 0;
// Wait Times // Wait Times
public static double rapidWaitTime = 0.5; public static double rapidWaitTime = 0.4;
public static double rapidShootTime = 0.8; public static double rapidShootTime = 0.45;
public static double openGate1Time = 1.5; public static double openGate1Time = 1.5;
public static double openGate2Time = 1.5; public static double openGate2Time = 1.5;
public static double openGateWaitTime = 5; public static double openGateWaitTimeMax = 3;
public static double openGateWaitTimeMin = 1.75;
public static int maxLoopCycles = 3;
// Initialize path state machine // Initialize path state machine
private enum PathState { private enum PathState {
@@ -53,46 +56,48 @@ public class Auto21Ball_Front_Gate extends LinearOpMode {
PathState pathState = PathState.DRIVE_SHOOT0; PathState pathState = PathState.DRIVE_SHOOT0;
// Poses // Poses
public static double startPoseX = 55, startPoseY = 38, startPoseH = -90; public static double startPoseX = 55, startPoseY = 39, startPoseH = 0;
public static double shoot0X = 18, shoot0Y = 18, shoot0H = -30; public static double shoot0X = 25, shoot0Y = 18, shoot0H = 0;
public static double pickup1ControlX = 101.53321878579611, pickup1ControlY = 81.84077892325314; public static double pickup1ControlX = 29.53321878579611, pickup1ControlY = 9.84077892325314;
public static double pickup1X = 54, pickup1Y = 10, pickup1H = 0; public static double pickup1X = 50, pickup1Y = 10, pickup1H = 0;
public static double openGate1ControlX = 43.82989690721648, openGate1ControlY = 3.86540664375714; public static double openGate1ControlX = 43.82989690721648, openGate1ControlY = 3.86540664375714;
public static double openGate1X = 59, openGate1Y = 2, openGate1H = 0; public static double openGate1X = 59, openGate1Y = 2, openGate1H = 0;
public static double shoot1ControlX = 40, shoot1ControlY = 3; public static double shoot1ControlX = 40, shoot1ControlY = 3;
public static double shoot1X = 18, shoot1Y = 11, shoot1H = -30; public static double shoot1X = 25, shoot1Y = 11, shoot1H = -30;
public static double pickup2ControlX = 18, pickup2ControlY = -11; public static double pickup2ControlX = 18, pickup2ControlY = -18;
public static double pickup2X = 61, pickup2Y = -14.5, pickup2H = 0; public static double pickup2X = 61, pickup2Y = -14.5, pickup2H = 0;
public static double openGate2ControlX = 45.9782359679267, openGate2ControlY = -15.106643757159245; public static double openGate2ControlX = 45.9782359679267, openGate2ControlY = -15.106643757159245;
public static double openGate2X = 57, openGate2Y = -8, openGate2H = 0; public static double openGate2X = 57, openGate2Y = -8, openGate2H = 0;
public static double shoot2ControlX = 57, shoot2ControlY = -8; public static double shoot2ControlX = 57, shoot2ControlY = -8;
public static double shoot2X = 18, shoot2Y = 11, shoot2H = -30; public static double shoot2X = 25, shoot2Y = 11, shoot2H = -30;
public static double intakeGateControlX = 59, intakeGateControlY = 60; public static double intakeGateControlX = 61, intakeGateControlY = -11;
public static double intakeGateX = 59, intakeGateY = -12, intakeGateH = 20; public static double intakeGateX = 61, intakeGateY = -11, intakeGateH = 20;
public static double shootGateControlX = 59, shootGateControlY = -12; public static double shootGateControlX = 56, shootGateControlY = -10;
public static double shootGateX = 18, shootGateY = 11, shootGateH = -30; public static double shootGateX = 25, shootGateY = 11, shootGateH = -30;
public static double shootLeaveControlX = 59, shootLeaveControlY = -12; public static double shootLeaveControlX = 56, shootLeaveControlY = -10;
public static double shootLeaveX = 14, shootLeaveY = 40, shootLeaveH = -50; public static double shootLeaveX = 16, shootLeaveY = 36, shootLeaveH = -50;
public static double leaveX = 45, leaveY = 10, leaveH = 0;
public static double awayFromGateX = 40, awayFromGateY = -12, awayFromGateH = 0;
double[] xPoses = {startPoseX, shoot0X, double[] xPoses = {startPoseX, shoot0X,
pickup1ControlX, pickup1X, openGate1ControlX, openGate1X, shoot1ControlX, shoot1X, pickup1ControlX, pickup1X, openGate1ControlX, openGate1X, shoot1ControlX, shoot1X,
pickup2ControlX, pickup2X, openGate2ControlX, openGate2X, shoot2ControlX, shoot2X, pickup2ControlX, pickup2X, openGate2ControlX, openGate2X, shoot2ControlX, shoot2X,
intakeGateControlX, intakeGateX, shootGateControlX, shootGateX, intakeGateControlX, intakeGateX, shootGateControlX, shootGateX,
shootLeaveControlX, shootLeaveX}; shootLeaveControlX, shootLeaveX, leaveX, awayFromGateX};
double[] yPoses = {startPoseY, shoot0Y, double[] yPoses = {startPoseY, shoot0Y,
pickup1ControlY, pickup1Y, openGate1ControlY, openGate1Y, shoot1ControlY, shoot1Y, pickup1ControlY, pickup1Y, openGate1ControlY, openGate1Y, shoot1ControlY, shoot1Y,
pickup2ControlY, pickup2Y, openGate2ControlY, openGate2Y, shoot2ControlY, shoot2Y, pickup2ControlY, pickup2Y, openGate2ControlY, openGate2Y, shoot2ControlY, shoot2Y,
intakeGateControlY, intakeGateY, shootGateControlY, shootGateY, intakeGateControlY, intakeGateY, shootGateControlY, shootGateY,
shootLeaveControlY, shootLeaveY}; shootLeaveControlY, shootLeaveY, leaveY, awayFromGateY};
double[] headings = {startPoseH, shoot0H, double[] headings = {startPoseH, shoot0H,
0, pickup1H, 0, openGate1H, 0, shoot1H, 0, pickup1H, 0, openGate1H, 0, shoot1H,
0, pickup2H, 0, openGate2H, 0, shoot2H, 0, pickup2H, 0, openGate2H, 0, shoot2H,
0, intakeGateH, 0, shootGateH, 0, intakeGateH, 0, shootGateH,
0, shootLeaveH}; 0, shootLeaveH, leaveH, awayFromGateH};
Pose startPose, shoot0, Pose startPose, shoot0,
pickup1Control, pickup1, openGate1Control, openGate1, shoot1Control, shoot1, pickup1Control, pickup1, openGate1Control, openGate1, shoot1Control, shoot1,
pickup2Control, pickup2, openGate2Control, openGate2, shoot2Control, shoot2, pickup2Control, pickup2, openGate2Control, openGate2, shoot2Control, shoot2,
intakeGateControl, intakeGate, shootGateControl, shootGate, intakeGateControl, intakeGate, shootGateControl, shootGate,
shootLeaveControl, shootLeave; shootLeaveControl, shootLeave, leave, awayFromGate;
private void initializePoses(){ private void initializePoses(){
startPose = new Pose(xPoses[0], yPoses[0], Math.toRadians(headings[0])); startPose = new Pose(xPoses[0], yPoses[0], Math.toRadians(headings[0]));
shoot0 = new Pose(xPoses[1], yPoses[1], Math.toRadians(headings[1])); shoot0 = new Pose(xPoses[1], yPoses[1], Math.toRadians(headings[1]));
@@ -114,12 +119,14 @@ public class Auto21Ball_Front_Gate extends LinearOpMode {
shootGate = new Pose(xPoses[17], yPoses[17], Math.toRadians(headings[17])); shootGate = new Pose(xPoses[17], yPoses[17], Math.toRadians(headings[17]));
shootLeaveControl = new Pose(xPoses[18], yPoses[18]); shootLeaveControl = new Pose(xPoses[18], yPoses[18]);
shootLeave = new Pose(xPoses[19], yPoses[19], Math.toRadians(headings[19])); shootLeave = new Pose(xPoses[19], yPoses[19], Math.toRadians(headings[19]));
leave = new Pose(xPoses[20], yPoses[20], Math.toRadians(headings[20]));
awayFromGate = new Pose(xPoses[21], yPoses[21], Math.toRadians(headings[21]));
} }
//Building Paths //Building Paths
PathChain startPose_shoot0, shoot0_pickup1, pickup1_openGate1, openGate1_shoot1, PathChain startPose_shoot0, shoot0_pickup1, pickup1_openGate1, openGate1_shoot1,
shoot1_pickup2, pickup2_openGate2, openGate2_shoot2, shoot1_pickup2, pickup2_openGate2, openGate2_shoot2,
shoot2_intakeGate, intakeGate_shootGate, shootGate_intakeGate, intakeGate_shootLeave; shoot2_intakeGate, intakeGate_shootGate, shootGate_intakeGate, intakeGate_shootLeave, shootGate_leave, intakeGate_awayFromGate;
private void buildPaths(){ private void buildPaths(){
startPose_shoot0 = follower.pathBuilder() startPose_shoot0 = follower.pathBuilder()
.addPath(new BezierLine(startPose, shoot0)) .addPath(new BezierLine(startPose, shoot0))
@@ -175,18 +182,29 @@ public class Auto21Ball_Front_Gate extends LinearOpMode {
.addPath(new BezierCurve(intakeGate, shootLeaveControl, shootLeave)) .addPath(new BezierCurve(intakeGate, shootLeaveControl, shootLeave))
.setLinearHeadingInterpolation(intakeGate.getHeading(), shootLeave.getHeading()) .setLinearHeadingInterpolation(intakeGate.getHeading(), shootLeave.getHeading())
.build(); .build();
shootGate_leave = follower.pathBuilder()
.addPath(new BezierLine(shootGate, leave))
.setLinearHeadingInterpolation(shootGate.getHeading(), leave.getHeading())
.build();
intakeGate_awayFromGate = follower.pathBuilder()
.addPath(new BezierLine(intakeGate, awayFromGate))
.setLinearHeadingInterpolation(intakeGate.getHeading(), awayFromGate.getHeading())
.build();
} }
//Path State Machine //Path State Machine
private boolean startAuto = true; private boolean startAuto = true;
private double timeStamp = 0; private double timeStamp = 0;
private int cycle = 0;
private void pathStateMachine(){ private void pathStateMachine(){
double currentTime = (double) System.currentTimeMillis() / 1000; double currentTime = (double) System.currentTimeMillis() / 1000;
switch(pathState){ switch(pathState){
case DRIVE_SHOOT0: case DRIVE_SHOOT0:
spindexer.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID); spindexer.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
shooter.setFlywheelVelocity(2400); shooter.setFlywheelVelocity(2300);
robot.setHoodPos(0.64); robot.setHoodPos(0.68);
if (startAuto){ if (startAuto){
follower.followPath(startPose_shoot0, false); follower.followPath(startPose_shoot0, false);
startAuto = false; startAuto = false;
@@ -241,7 +259,7 @@ public class Auto21Ball_Front_Gate extends LinearOpMode {
case PICKUP2: case PICKUP2:
if (!follower.isBusy()){ if (!follower.isBusy()){
follower.followPath(pickup2_openGate2, false); follower.followPath(pickup2_openGate2, false);
pathState = PathState.DRIVE_SHOOT2; pathState = PathState.OPENGATE2;
timeStamp = currentTime; timeStamp = currentTime;
} }
break; break;
@@ -271,9 +289,18 @@ public class Auto21Ball_Front_Gate extends LinearOpMode {
} }
break; break;
case INTAKE_GATE: case INTAKE_GATE:
if (currentTime - timeStamp > openGateWaitTime){ if ((currentTime - timeStamp > openGateWaitTimeMax || (robot.insideBeam.isPressed() && robot.outsideBeam.isPressed()))
follower.followPath(openGate1_shoot1, false); && (currentTime - timeStamp > openGateWaitTimeMin)){
pathState = PathState.DRIVE_SHOOT1; if (getRuntime() - runtime > 27){
follower.followPath(intakeGate_awayFromGate, true);
pathState = PathState.WAIT_SHOOT_LEAVE;
} else if (getRuntime() - runtime > 22 || cycle >= maxLoopCycles - 1){
follower.followPath(intakeGate_shootLeave, true);
pathState = PathState.DRIVE_SHOOT_LEAVE;
} else {
follower.followPath(intakeGate_shootGate, false);
pathState = PathState.DRIVE_SHOOT_GATE;
}
timeStamp = currentTime; timeStamp = currentTime;
} }
// TODO: add logic to shoot gate // TODO: add logic to shoot gate
@@ -291,8 +318,14 @@ public class Auto21Ball_Front_Gate extends LinearOpMode {
if (currentTime - timeStamp > rapidShootTime || if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE && (spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){ spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
follower.followPath(shootGate_intakeGate, false); cycle++;
pathState = PathState.INTAKE_GATE; if (getRuntime() - runtime > 24 || cycle >= maxLoopCycles){
follower.followPath(shootGate_leave, true);
pathState = PathState.WAIT_SHOOT_LEAVE;
} else {
follower.followPath(shootGate_intakeGate, false);
pathState = PathState.INTAKE_GATE;
}
timeStamp = currentTime; timeStamp = currentTime;
} }
break; break;
@@ -311,7 +344,7 @@ public class Auto21Ball_Front_Gate extends LinearOpMode {
default: default:
break; break;
} }
TELE.update(); // use for debugging TELE.addData("Moving?", follower.isBusy());
} }
// Used for changing alliance // Used for changing alliance
@@ -343,6 +376,7 @@ public class Auto21Ball_Front_Gate extends LinearOpMode {
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander); shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
spindexer = new SpindexerTransferIntake(robot, TELE, commander); spindexer = new SpindexerTransferIntake(robot, TELE, commander);
ParkTilter park = new ParkTilter(robot); ParkTilter park = new ParkTilter(robot);
boolean startAuto = true;
boolean initializeRobot = false; boolean initializeRobot = false;
while (opModeInInit()){ while (opModeInInit()){
@@ -391,6 +425,14 @@ public class Auto21Ball_Front_Gate extends LinearOpMode {
if (isStopRequested()) return; if (isStopRequested()) return;
while (opModeIsActive()){ while (opModeIsActive()){
if (startAuto){
runtime = getRuntime();
startAuto = false;
}
park.unpark();
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR); shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
shooter.update(robot.voltage.getVoltage()); shooter.update(robot.voltage.getVoltage());

View File

@@ -33,6 +33,10 @@ public class TeleopV4 extends LinearOpMode {
public static Pose relocalizePose = new Pose(56, 11, 0); public static Pose relocalizePose = new Pose(56, 11, 0);
public static Pose teleStart = new Pose(0,0,0); public static Pose teleStart = new Pose(0,0,0);
private boolean firstTickFull = true;
private boolean intakeFull = true;
private boolean shooting = false;
@Override @Override
public void runOpMode() throws InterruptedException { public void runOpMode() throws InterruptedException {
@@ -77,16 +81,37 @@ public class TeleopV4 extends LinearOpMode {
TELE.addData("TELE START", teleStart); TELE.addData("TELE START", teleStart);
TELE.update(); TELE.update();
while (opModeInInit()){
if (gamepad1.triangleWasPressed()){
VelocityCommander.lockFront = true;
VelocityCommander.lockBack = false;
} else if (gamepad1.squareWasPressed()){
VelocityCommander.lockBack = true;
VelocityCommander.lockFront = false;
} else if (gamepad1.circleWasPressed()){
VelocityCommander.lockBack = false;
VelocityCommander.lockFront = false;
}
TELE.addLine("Initialization is done");
TELE.addData("Starting Position", follower.getPose());
TELE.addData("TELE START", teleStart);
TELE.addData("Front?:", VelocityCommander.lockFront);
TELE.addData("Back?:", VelocityCommander.lockBack);
TELE.update();
}
waitForStart(); waitForStart();
if (isStopRequested()) return; if (isStopRequested()) return;
int emptyTicks = 0;
while (opModeIsActive()) { while (opModeIsActive()) {
//Drivetrain //Drivetrain
drivetrain.drive( drivetrain.drive(
-gamepad1.right_stick_y, -gamepad1.right_stick_y,
gamepad1.right_stick_x, gamepad1.right_stick_x,
gamepad1.left_stick_x gamepad1.left_stick_x,
gamepad1.left_trigger
); );
if (gamepad1.crossWasPressed()){ if (gamepad1.crossWasPressed()){
@@ -114,7 +139,23 @@ public class TeleopV4 extends LinearOpMode {
if (shooter.getState() == Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR || shooter.getState() == Shooter.ShooterState.MANUAL){ if (shooter.getState() == Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR || shooter.getState() == Shooter.ShooterState.MANUAL){
shooter.setFlywheelVelocity(2500); shooter.setFlywheelVelocity(2500);
robot.setHoodPos(0.6); robot.setHoodPos(0.6);
robot.setTransferPower(-0.8); }
if (gamepad1.triangleWasPressed()){
VelocityCommander.lockFront = true;
VelocityCommander.lockBack = false;
TELE.addData("Front?:", true);
TELE.addData("Back?:", false);
} else if (gamepad1.squareWasPressed()){
VelocityCommander.lockBack = true;
VelocityCommander.lockFront = false;
TELE.addData("Front?:", false);
TELE.addData("Back?:", true);
} else if (gamepad1.circleWasPressed()){
VelocityCommander.lockBack = false;
VelocityCommander.lockFront = false;
TELE.addData("Front?:", false);
TELE.addData("Back?:", true);
} }
shooter.update(robot.voltage.getVoltage()); shooter.update(robot.voltage.getVoltage());
@@ -131,6 +172,25 @@ public class TeleopV4 extends LinearOpMode {
state == SpindexerTransferIntake.RapidMode.HOLD_BALLS)) { state == SpindexerTransferIntake.RapidMode.HOLD_BALLS)) {
spindexerTransferIntake.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE); spindexerTransferIntake.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
intakeFull = false;
firstTickFull = true;
shooting = true;
}
if (state != SpindexerTransferIntake.RapidMode.OPEN_GATE && state != SpindexerTransferIntake.RapidMode.SHOOT){
shooting = false;
}
if (robot.insideBeam.isPressed() && robot.outsideBeam.isPressed() && !shooting){
intakeFull = true;
} else {
intakeFull = false;
firstTickFull = true;
}
if (intakeFull && firstTickFull){
gamepad1.rumble(100);
firstTickFull = false;
} }
if (gamepad1.right_trigger > 0.5 && if (gamepad1.right_trigger > 0.5 &&
@@ -144,6 +204,7 @@ public class TeleopV4 extends LinearOpMode {
if (gamepad1.right_bumper && state != SpindexerTransferIntake.RapidMode.OPEN_GATE && state != SpindexerTransferIntake.RapidMode.SHOOT) { if (gamepad1.right_bumper && state != SpindexerTransferIntake.RapidMode.OPEN_GATE && state != SpindexerTransferIntake.RapidMode.SHOOT) {
robot.setIntakePower(1); robot.setIntakePower(1);
robot.setTransferPower(-0.7);
} }
if (gamepad2.leftBumperWasPressed()){ if (gamepad2.leftBumperWasPressed()){
@@ -159,20 +220,20 @@ public class TeleopV4 extends LinearOpMode {
} }
loopTimes.loop(); loopTimes.loop();
TELE.addData("Loop Time Average", loopTimes.getAvgLoopTime()); // TELE.addData("Loop Time Average", loopTimes.getAvgLoopTime());
TELE.addData("Loop Time Max", loopTimes.getMaxLoopTimeOneMin()); // TELE.addData("Loop Time Max", loopTimes.getMaxLoopTimeOneMin());
TELE.addData("Loop Time Min", loopTimes.getMinLoopTimeOneMin()); // TELE.addData("Loop Time Min", loopTimes.getMinLoopTimeOneMin());
//
TELE.addData("Distance From Goal", commander.getDistance()); TELE.addData("Distance From Goal", commander.getDistance());
TELE.addData("Hood Position", commander.getHoodPredicted()); // TELE.addData("Hood Position", commander.getHoodPredicted());
TELE.addData("Transfer Power", robot.transfer.getPower()); // TELE.addData("Transfer Power", robot.transfer.getPower());
TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM()); TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM());
TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity()); TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity());
//
TELE.addData("Current Position", currentPose); // TELE.addData("Current Position", currentPose);
//
TELE.addData("Current LL Pipeline", turret.pipeline()); // TELE.addData("Current LL Pipeline", turret.pipeline());
//
TELE.update(); TELE.update();
} }

View File

@@ -32,7 +32,7 @@ public class NewShooterTest extends LinearOpMode {
public static int flywheelVelo = 0; public static int flywheelVelo = 0;
public static double hoodPos = 0.5; public static double hoodPos = 0.5;
public static double transferPower = -0.8; public static double transferPower = -0.8;
// public static double turretPos = 0.51; public static boolean overrideTransferPower = false;
@Override @Override
public void runOpMode() throws InterruptedException { public void runOpMode() throws InterruptedException {
@@ -81,16 +81,18 @@ public class NewShooterTest extends LinearOpMode {
drivetrain.drive( drivetrain.drive(
-gamepad1.right_stick_y, -gamepad1.right_stick_y,
gamepad1.right_stick_x, gamepad1.right_stick_x,
gamepad1.left_stick_x gamepad1.left_stick_x,
gamepad1.left_trigger
); );
if (gamepad1.crossWasPressed()){ if (gamepad1.crossWasPressed()){
if (Color.redAlliance){ if (Color.redAlliance){
TeleopV4.relocalizePose = new Pose(56, 11, 0); TeleopV4.relocalizePose = new Pose(57.5, 5, 0);
} else { } else {
TeleopV4.relocalizePose = new Pose(-56, 11, 180); TeleopV4.relocalizePose = new Pose(-57.5, 5, Math.toRadians(180));
} }
follower.setPose(TeleopV4.relocalizePose); follower.setPose(TeleopV4.relocalizePose);
sleep(500);
gamepad1.rumble(100); gamepad1.rumble(100);
} }
@@ -107,7 +109,6 @@ public class NewShooterTest extends LinearOpMode {
if (shooter.getState() == Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR || shooter.getState() == Shooter.ShooterState.MANUAL){ if (shooter.getState() == Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR || shooter.getState() == Shooter.ShooterState.MANUAL){
shooter.setFlywheelVelocity(flywheelVelo); shooter.setFlywheelVelocity(flywheelVelo);
robot.setHoodPos(hoodPos); robot.setHoodPos(hoodPos);
robot.setTransferPower(transferPower);
} }
@@ -156,6 +157,7 @@ public class NewShooterTest extends LinearOpMode {
TELE.addData("Hood Position", commander.getHoodPredicted()); TELE.addData("Hood Position", commander.getHoodPredicted());
TELE.addData("Transfer Power", commander.getTransferPow()); TELE.addData("Transfer Power", commander.getTransferPow());
TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM()); TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM());
TELE.addData("Manuel Velocity RPM", flywheelVelo);
TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity()); TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity());
TELE.addData("TX:", turret.getTX()); TELE.addData("TX:", turret.getTX());

View File

@@ -91,7 +91,8 @@ public class SortedSpindexerTest extends LinearOpMode {
drivetrain.drive( drivetrain.drive(
-gamepad1.right_stick_y, -gamepad1.right_stick_y,
gamepad1.right_stick_x, gamepad1.right_stick_x,
gamepad1.left_stick_x gamepad1.left_stick_x,
gamepad1.left_trigger
); );
follower.update(); follower.update();

View File

@@ -37,7 +37,7 @@ public class Drivetrain {
tele = input; tele = input;
} }
public void drive(double y, double x, double rx) { public void drive(double y, double x, double rx, double stop) {
boolean snappedForward = false; boolean snappedForward = false;
boolean snappedStrafe = false; boolean snappedStrafe = false;
@@ -79,18 +79,30 @@ public class Drivetrain {
robot.setFrontRightPower(frontRightPower); robot.setFrontRightPower(frontRightPower);
robot.setBackRightPower(backRightPower); robot.setBackRightPower(backRightPower);
if (tele) { if (stop > 0.5){
robot.frontLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
telemetry.addData("Forward Snap", snappedForward); robot.backLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
telemetry.addData("Strafe Snap", snappedStrafe); robot.frontRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
robot.backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
telemetry.addData("Correction RX", correctionRX);
telemetry.addData("FL", frontLeftPower);
telemetry.addData("BL", backLeftPower);
telemetry.addData("FR", frontRightPower);
telemetry.addData("BR", backRightPower);
robot.setFrontLeftPower(0);
robot.setBackLeftPower(0);
robot.setFrontRightPower(0);
robot.setBackRightPower(0);
} }
// if (tele) {
//
// telemetry.addData("Forward Snap", snappedForward);
// telemetry.addData("Strafe Snap", snappedStrafe);
//
// telemetry.addData("Correction RX", correctionRX);
//
// telemetry.addData("FL", frontLeftPower);
// telemetry.addData("BL", backLeftPower);
// telemetry.addData("FR", frontRightPower);
// telemetry.addData("BR", backRightPower);
//
// }
} }
} }

View File

@@ -1,6 +1,8 @@
package org.firstinspires.ftc.teamcode.utilsv2; package org.firstinspires.ftc.teamcode.utilsv2;
import com.acmerobotics.dashboard.config.Config; import com.acmerobotics.dashboard.config.Config;
import com.arcrobotics.ftclib.controller.PIDFController;
import com.arcrobotics.ftclib.controller.wpilibcontroller.SimpleMotorFeedforward;
import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.HardwareMap; import com.qualcomm.robotcore.hardware.HardwareMap;
@@ -16,10 +18,20 @@ public class Flywheel {
// public PIDFCoefficients shooterPIDF1, shooterPIDF2; // public PIDFCoefficients shooterPIDF1, shooterPIDF2;
public static PIDFCoefficients shooterPIDF; public static PIDFCoefficients shooterPIDF;
PIDFController pidf;
SimpleMotorFeedforward feedforward;
public static double kS = 0.01; // Static feedforward
public static double kV = 0.0001935; // Velocity feedforward
public static double shooterPIDF_P = 500; public static double shooterPIDF_P = 500;
public static double shooterPIDF_I = 1; public static double shooterPIDF_I = 1;
public static double shooterPIDF_D = 0.0; public static double shooterPIDF_D = 0.0;
public static double shooterPIDF_F = 93; public static double shooterPIDF_F = 93;
// public static double shooterPIDF_P = 0.0001;
// public static double shooterPIDF_I = 0;
// public static double shooterPIDF_D = 0.00001;
// public static double shooterPIDF_F = 0;
private double velo = 0.0; private double velo = 0.0;
private double velo1 = 0.0; private double velo1 = 0.0;
@@ -36,6 +48,8 @@ public class Flywheel {
public Flywheel(Robot rob) { public Flywheel(Robot rob) {
robot = rob; robot = rob;
shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / 12); shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / 12);
// pidf = new PIDFController(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, 0);
// feedforward = new SimpleMotorFeedforward(kS, kV);
} }
public double getVelo() { public double getVelo() {
@@ -67,19 +81,23 @@ public class Flywheel {
shooterPIDF.d = d; shooterPIDF.d = d;
shooterPIDF.f = f; shooterPIDF.f = f;
// pidf.setPIDF(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, 0);
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF); robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
} }
private double prevF = 0; private double prevF = 0;
public static double voltagePIDFDifference = 1; public static double voltagePIDFDifference = 1;
double averageVoltage = 0;
public void setF(double voltage){ public void setF(double voltage){
averageVoltage = ALPHA * voltage + (1 - ALPHA) * averageVoltage;
double f = shooterPIDF_F / voltage; double f = shooterPIDF_F / voltage;
if (Math.abs(prevF - f) > voltagePIDFDifference) { if (Math.abs(prevF - f) > voltagePIDFDifference && !steady) {
shooterPIDF.f = f; shooterPIDF.f = f;
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF); robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
prevF = f;
} }
prevF = f;
} }
// Convert from RPM to Ticks per Second // Convert from RPM to Ticks per Second
@@ -92,25 +110,30 @@ public class Flywheel {
return (TPS * 60.0) / 28.0; return (TPS * 60.0) / 28.0;
} }
double ALPHA = 0.3;
private void updateVelocityAverage(double newVelocity) { private void updateVelocityAverage(double newVelocity) {
velocityHistory.add(newVelocity); // velocityHistory.add(newVelocity);
//
// int velocityHistorySize = 5;
// if (velocityHistory.size() > velocityHistorySize) {
// velocityHistory.removeFirst();
// }
//
// double sum = 0.0;
//
// for (double v : velocityHistory) {
// sum += v;
// }
//
// averageVelocity = sum / velocityHistory.size();
int velocityHistorySize = 5; averageVelocity = ALPHA * newVelocity + (1 - ALPHA) * averageVelocity;
if (velocityHistory.size() > velocityHistorySize) {
velocityHistory.removeFirst();
}
double sum = 0.0;
for (double v : velocityHistory) {
sum += v;
}
averageVelocity = sum / velocityHistory.size();
} }
double power; double power;
double prevTargetTime = 0;
double prevTargetVelocity = 0;
public void manageFlywheel(double commandedVelocity) { public void manageFlywheel(double commandedVelocity) {
if (Math.abs(targetVelocity - commandedVelocity) > 0.0001) { if (Math.abs(targetVelocity - commandedVelocity) > 0.0001) {
@@ -125,13 +148,12 @@ public class Flywheel {
velo2 = TPS_to_RPM(robot.shooter2.getVelocity()); velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
velo = (velo1 + velo2) / 2.0; velo = velo1;
updateVelocityAverage(velo); updateVelocityAverage(velo);
steady = (Math.abs(commandedVelocity - averageVelocity) < 50); steady = (Math.abs(commandedVelocity - averageVelocity) < 50);
} }
public double getShooterPower(){return power;} public double getShooterPower(){return power;}
} }

View File

@@ -104,7 +104,8 @@ public class Shooter {
follow.getAcceleration().getXComponent(), follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(), follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent(), follow.getAcceleration().getYComponent(),
voltage voltage,
fly.getAverageVelocity()
); );
fly.manageFlywheel(flywheelVelocity); fly.manageFlywheel(flywheelVelocity);
@@ -131,7 +132,8 @@ public class Shooter {
follow.getAcceleration().getXComponent(), follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(), follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent(), follow.getAcceleration().getYComponent(),
voltage voltage,
fly.getAverageVelocity()
); );
flywheelVelocity = commander.getPredictedRPM(); flywheelVelocity = commander.getPredictedRPM();
@@ -153,7 +155,8 @@ public class Shooter {
follow.getAcceleration().getXComponent(), follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(), follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent(), follow.getAcceleration().getYComponent(),
voltage voltage,
fly.getAverageVelocity()
); );
flywheelVelocity = commander.getPredictedRPM(); flywheelVelocity = commander.getPredictedRPM();
@@ -172,7 +175,8 @@ public class Shooter {
follow.getAcceleration().getXComponent(), follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(), follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent(), follow.getAcceleration().getYComponent(),
voltage voltage,
fly.getAverageVelocity()
); );
flywheelVelocity = commander.getPredictedRPM(); flywheelVelocity = commander.getPredictedRPM();
@@ -200,7 +204,8 @@ public class Shooter {
follow.getAcceleration().getXComponent(), follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(), follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent(), follow.getAcceleration().getYComponent(),
voltage voltage,
fly.getAverageVelocity()
); );
fly.manageFlywheel(flywheelVelocity); fly.manageFlywheel(flywheelVelocity);
fly.setPIDF(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / voltage); fly.setPIDF(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / voltage);

View File

@@ -276,20 +276,20 @@ public class SpindexerTransferIntake {
private int holdBallsTicker = 0; private int holdBallsTicker = 0;
public void update() { public void update() {
TELE.addData("Sorted State", sortedIntakeStates); // TELE.addData("Sorted State", sortedIntakeStates);
TELE.addData("Ball0", ballColors[0]); // TELE.addData("Ball0", ballColors[0]);
TELE.addData("Ball1", ballColors[1]); // TELE.addData("Ball1", ballColors[1]);
TELE.addData("Ball2", ballColors[2]); // TELE.addData("Ball2", ballColors[2]);
//
TELE.addData("Shoot0", shootOrder[0]); // TELE.addData("Shoot0", shootOrder[0]);
TELE.addData("Shoot1", shootOrder[1]); // TELE.addData("Shoot1", shootOrder[1]);
TELE.addData("Shoot2", shootOrder[2]); // TELE.addData("Shoot2", shootOrder[2]);
//
TELE.addData("Color0", ballColors[0]); // TELE.addData("Color0", ballColors[0]);
TELE.addData("Color1", ballColors[1]); // TELE.addData("Color1", ballColors[1]);
TELE.addData("Color2", ballColors[2]); // TELE.addData("Color2", ballColors[2]);
//
TELE.addData("Shoot State", shootState); // TELE.addData("Shoot State", shootState);
switch (mode) { switch (mode) {
@@ -317,9 +317,13 @@ public class SpindexerTransferIntake {
if (robot.insideBeam.isPressed() && robot.revSensor.getDistance(DistanceUnit.CM) < sensorDistanceThreshold) { if (robot.insideBeam.isPressed() && robot.revSensor.getDistance(DistanceUnit.CM) < sensorDistanceThreshold) {
setRapidMode(RapidMode.TRANSFER_OFF); holdBallsTicker++;
} }
if (holdBallsTicker > 10){
setRapidMode(RapidMode.TRANSFER_OFF);
holdBallsTicker = 0;
}
break; break;
@@ -366,9 +370,11 @@ public class SpindexerTransferIntake {
case HOLD_BALLS: case HOLD_BALLS:
if (robot.insideBeam.isPressed() if (robot.insideBeam.isPressed()
&& robot.outsideBeam.isPressed() && holdBallsTicker > 5) { && robot.outsideBeam.isPressed()) {
robot.setTransferPower(0);
robot.setIntakePower(0.1); robot.setIntakePower(0.1);
robot.setTransferServoPos(ServoPositions.transferServo_in);
} else { } else {
holdBallsTicker++; holdBallsTicker++;
@@ -378,37 +384,42 @@ public class SpindexerTransferIntake {
case OPEN_GATE: case OPEN_GATE:
robot.setRapidFireBlockerPos(
ServoPositions.rapidFireBlocker_Open
);
if (stateTime() >= 100) { if (stateTime() >= 100) {
setRapidMode(RapidMode.SHOOT); setRapidMode(RapidMode.SHOOT);
} }
robot.setTransferServoPos(ServoPositions.transferServo_in);
robot.setRapidFireBlockerPos(
ServoPositions.rapidFireBlocker_Open
);
if (Shooter.manualFlywheel) { if (Shooter.manualFlywheel) {
robot.setTransferPower(NewShooterTest.transferPower); robot.setTransferPower(NewShooterTest.transferPower);
robot.setIntakePower(-NewShooterTest.transferPower);
} else { } else {
robot.setTransferPower(commander.getTransferPow()); robot.setTransferPower(commander.getTransferPow());
robot.setIntakePower(-commander.getTransferPow());
} }
break; break;
case SHOOT: case SHOOT:
robot.setTransferServoPos( if (stateTime() >= 500) {
ServoPositions.transferServo_in
);
if (stateTime() >= 400) {
setRapidMode(RapidMode.INTAKE); setRapidMode(RapidMode.INTAKE);
} }
if (Shooter.manualFlywheel) { if (Shooter.manualFlywheel) {
robot.setTransferPower(NewShooterTest.transferPower); robot.setTransferPower(NewShooterTest.transferPower);
robot.setIntakePower(-NewShooterTest.transferPower);
} else { } else {
robot.setTransferPower(commander.getTransferPow()); robot.setTransferPower(commander.getTransferPow());
robot.setIntakePower(-commander.getTransferPow());
} }
holdBallsTicker = 0;
break; break;
} }
break; break;

View File

@@ -20,12 +20,12 @@ public class Turret {
private final double turretMin = 0.05; private final double turretMin = 0.05;
private final double turretMax = 0.95; private final double turretMax = 0.95;
public static boolean limelightUsed = true; public static boolean limelightUsed = true;
public static double B_PID_P = 0.0003, B_PID_I = 0.0, B_PID_D = 0.00003; public static double B_PID_P = 0.0001, B_PID_I = 0.0, B_PID_D = 0.000005;
LLResult result; LLResult result;
PIDController bearingPID; PIDController bearingPID;
boolean bearingAligned = false; boolean bearingAligned = false;
public int LL_COAST_TICKS = 5; public int LL_COAST_TICKS = 5;
public static double TARGET_POSITION_TOLERANCE = 0.5; public static double TARGET_POSITION_TOLERANCE = 0.65;
public static double alphaTX = 0.5; public static double alphaTX = 0.5;
private double targetTx = 0; private double targetTx = 0;
private double currentTrackOffset = 0; private double currentTrackOffset = 0;

View File

@@ -8,88 +8,71 @@ public class VelocityCommander {
public static double xAccK = 0.025; // TODO: Tune public static double xAccK = 0.025; // TODO: Tune
public static double yVelK = 0.05; // TODO: Tune public static double yVelK = 0.05; // TODO: Tune
public static double yAccK = 0.025; // TODO: Tune public static double yAccK = 0.025; // TODO: Tune
public static boolean lockFront = false;
public static boolean lockBack = false;
public static int farBound = 140;
public static int closeBound = 110;
public static double errorHoodAdjustment = 0.0005;
private double hoodPos = 0.88; private double hoodPos = 0.88;
private double transferPow = -1; private double transferPow = -1;
private int velo = 0; private int velo = 0;
public VelocityCommander() {} public VelocityCommander() {}
private final double veloA = -2.703087757*Math.pow(10, -14); final double veloA = -0.00000133612;
private final double veloB = 2.904756341*Math.pow(10, -11); final double veloB = 0.000542733;
private final double veloC = -1.381814293*Math.pow(10, -8); final double veloC = -0.0739531;
private final double veloD = 0.000003829224585; final double veloD = 5.16759;
private final double veloE = -0.000684090204; final double veloE = 62.45781;
private final double veloF = 0.0822754689;
private final double veloG = -6.743119277;
private final double veloH = 371.7359504;
private final double veloI = -13189.70958;
private final double veloJ = 272005.7124;
private final double veloK = -2474581.713;
private double distToRPM (double dist){ private double distToRPM (double dist){
double currentVelo = 0; double currentVelo;
if (dist < 49) { if (lockFront && dist > closeBound){
currentVelo = 2000; dist = closeBound;
} else if (dist > 165){ } else if (lockBack && dist < farBound){
velo = 3760; dist = farBound;
} else { }
currentVelo = veloA*Math.pow(dist, 10) + if (dist < 54) {
veloB*Math.pow(dist, 9) + velo = 2000;
veloC*Math.pow(dist, 8) + } else if (dist > 181){
veloD*Math.pow(dist, 7) + velo = 3600;
veloE*Math.pow(dist, 6) + } else {
veloF*Math.pow(dist, 5) + currentVelo = veloA*Math.pow(dist, 4) +
veloG*Math.pow(dist, 4) + veloB*Math.pow(dist, 3) +
veloH*Math.pow(dist, 3) + veloC*Math.pow(dist, 2) +
veloI*Math.pow(dist, 2) + veloD*Math.pow(dist, 1) +
veloJ*Math.pow(dist, 1) + veloE;
veloK; velo = 10 * Math.round((float) Math.max(200, Math.min(360, currentVelo)));
} }
velo = Math.round((float) Math.max(2000, Math.min(3760, currentVelo)));
return velo; return velo;
} }
private final double hoodA = -4.3276177*Math.pow(10, -13); final double hoodA = 9.04203*Math.pow(10, -8);
private final double hoodB = 2.68062979*Math.pow(10, -10); final double hoodB = -0.0000204165;
private final double hoodC = -7.12859632*Math.pow(10, -8); final double hoodC = -0.00252089;
private final double hoodD = 0.0000106010785; final double hoodD = 1.06154;
private final double hoodE = -0.000960693973;
private final double hoodF = 0.0540375808;
private final double hoodG = -1.82724027;
private final double hoodH = 33.4797545;
private final double hoodI = -246.888632;
private void distToHood (double dist){ private void distToHood (double dist){
if (dist > 112){ if (dist > 174){
hoodPos = 0.35; hoodPos = 0.48;
} else if (dist < 49){ } else if (dist < 54){
hoodPos = 0.88; hoodPos = 0.88;
} else { } else {
hoodPos = hoodA*Math.pow(dist, 8) + hoodPos = hoodA*Math.pow(dist, 3) +
hoodB*Math.pow(dist, 7) + hoodB*Math.pow(dist, 2) +
hoodC*Math.pow(dist, 6) + hoodC*Math.pow(dist, 1) +
hoodD*Math.pow(dist, 5) + hoodD;
hoodE*Math.pow(dist, 4) +
hoodF*Math.pow(dist, 3) +
hoodG*Math.pow(dist, 2) +
hoodH*Math.pow(dist, 1) +
hoodI;
hoodPos = Math.max(0.35, Math.min(0.88, hoodPos));
} }
hoodPos = Math.max(0.48, Math.min(0.88, hoodPos));
} }
public double getHoodPredicted(){ public double getHoodPredicted(){
return hoodPos; return hoodPos;
} }
private void distToTransferPow(double dist, double voltage){ private void distToTransferPow(double dist, double voltage){
if (dist < 118){ if (dist < 140){
transferPow = -1; transferPow = -0.8;
} else if (dist < 125){
transferPow = -0.7;
} else { } else {
transferPow = -0.5; transferPow = -0.5;
} }
// transferPow = Math.max(-0.5, Math.min(-1, transferPow * (14/voltage)));
} }
public double getTransferPow(){return transferPow;} public double getTransferPow(){return transferPow;}
@@ -99,7 +82,7 @@ public class VelocityCommander {
} }
double predictedDist = 0; double predictedDist = 0;
public void getVeloPredictive(double dx, double dy, double xVel, double xAcc, double yVel, double yAcc, double voltage) { public void getVeloPredictive(double dx, double dy, double xVel, double xAcc, double yVel, double yAcc, double voltage, double velocity) {
double predictedDx = dx - (xVel * xVelK) - (0.5 * xAcc * xAccK); // Negative bc dx = target - robot double predictedDx = dx - (xVel * xVelK) - (0.5 * xAcc * xAccK); // Negative bc dx = target - robot
double predictedDy = dy - (yVel * yVelK) - (0.5 * yAcc * yAccK); // Negative bc dy = target - robot double predictedDy = dy - (yVel * yVelK) - (0.5 * yAcc * yAccK); // Negative bc dy = target - robot
@@ -110,6 +93,17 @@ public class VelocityCommander {
distToHood(predictedDist); distToHood(predictedDist);
distToTransferPow(predictedDist, voltage); distToTransferPow(predictedDist, voltage);
distToRPM(predictedDist); distToRPM(predictedDist);
hoodPos += adjustHood(predictedDist, velocity, velo);
}
public double adjustHood(double dist, double currentVelocity, double targetVelocity){
double error = targetVelocity - currentVelocity;
if (dist < farBound || error < 0){
error = 0;
}
System.out.println("Error "+ error);
return error * errorHoodAdjustment;
} }
public double getPredictedRPM(){return velo;} public double getPredictedRPM(){return velo;}