12 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
a9b57fd792 new autos 2026-06-06 23:15:26 -05:00
b09ba449b1 new autos 2026-06-06 23:14:06 -05:00
49a9e380d7 small changes 2026-06-06 21:52:04 -05:00
12cabd40db gate auto 2026-06-06 20:56:04 -05:00
351cff99ec oops 2026-06-06 20:53:40 -05:00
47ef898127 a lot of changes 2026-06-06 19:35:13 -05:00
d1626b20da fixed issues 2026-06-06 13:12:05 -05:00
e065084964 tele pose transfer 2026-06-05 18:51:54 -05:00
17 changed files with 1218 additions and 259 deletions

View File

@@ -32,8 +32,6 @@ import org.firstinspires.ftc.teamcode.utilsv2.Turret;
import java.util.List;
@Config
@Autonomous (preselectTeleOp = "TeleopV4")
public class Auto12BallPedroPathing extends LinearOpMode {
Robot robot;
MultipleTelemetry TELE;

View File

@@ -1,9 +1,6 @@
package org.firstinspires.ftc.teamcode.autonomous;
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseH;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseY;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseX;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
@@ -20,6 +17,7 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.teleop.TeleopV4;
import org.firstinspires.ftc.teamcode.utilsv2.*;
import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes;
@@ -39,9 +37,9 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
SpindexerTransferIntake spindexer;
// Wait Times
public static double sortedShootTime = 2;
public static double rapidWaitTime = 0.25;
public static double rapidShootTime = 1;
public static double sortedShootTime = 2.6;
public static double rapidWaitTime = 0.5;
public static double rapidShootTime = 0.8;
public static double openGateTime = 2.5;
public static double pushTime = 2;
@@ -59,45 +57,57 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
PathState pathState = PathState.PUSHBOT;
// Poses
public static double startPoseX = 91.5, startPoseY = 15, startPoseH = 90;
public static double pushBotX = 97, pushBotY = 18, pushBotH = 100;
public static double shoot0ControlX = 94.29667812142038, shoot0ControlY = 55.03493699885454;
public static double shoot0X = 95, shoot0Y = 83, shoot0H = 0;
public static double pickup1X = 126, pickup1Y = 82, pickup1H = 0;
public static double openGateControlX = 109.184421534937, openGateControlY = 74.24455899198165;
public static double openGateX = 131, openGateY = 74, openGateH = 0;
public static double shoot1ControlX = 112, shoot1ControlY = 75;
public static double shoot1X = 95, shoot1Y = 83, shoot1H = 0;
public static double drivePickup2X = 98, drivePickup2Y = 58.5, drivePickup2H = 0;
public static double pickup2X = 133, pickup2Y = 57, pickup2H = 0;
public static double shoot2ControlX = 102, shoot2ControlY = 63;
public static double shoot2X = 95, shoot2Y = 83, shoot2H = 0;
public static double drivePickup3X = 98, drivePickup3Y = 34.5, drivePickup3H = 0;
public static double pickup3X = 133, pickup3Y = 34.5, pickup3H = 0;
public static double shoot3ControlX = 97.62371134020621, shoot3ControlY = 34.813287514318446;
public static double shoot3X = 84, shoot3Y = 120, shoot3H = -90;
public static double startPoseX = 12, startPoseY = -64, startPoseH = 90;
public static double pushBotX = 19, pushBotY = -63, pushBotH = 100;
public static double shoot0ControlX = 16.29667812142038, shoot0ControlY = -19.67493699885454;
public static double shoot0X = 19, shoot0Y = 10, shoot0H = 0;
public static double pickup1X = 54, pickup1Y = 10, pickup1H = 0;
public static double openGateControlX = 37.184421534937, openGateControlY = 2.24455899198165;
public static double openGateX = 59, openGateY = 2, openGateH = 0;
public static double shoot1ControlX = 40, shoot1ControlY = 3;
public static double shoot1X = 19, shoot1Y = 10, shoot1H = 0;
public static double drivePickup2X = 26, drivePickup2Y = -14, drivePickup2H = 0;
public static double pickup2X = 61, pickup2Y = -14.5, pickup2H = 0;
public static double shoot2ControlX = 30, shoot2ControlY = -9;
public static double shoot2X = 19, shoot2Y = 10, shoot2H = 0;
public static double drivePickup3X = 26, drivePickup3Y = -37.5, drivePickup3H = 0;
public static double pickup3X = 61, pickup3Y = -37.5, pickup3H = 0;
public static double shoot3ControlX = 25.62371134020621, shoot3ControlY = -38.813287514318446;
public static double shoot3X = 12, shoot3Y = 40, shoot3H = -90;
double[] xPoses = {startPoseX, pushBotX, shoot0ControlX, shoot0X,
pickup1X, openGateControlX, openGateX, shoot1ControlX, shoot1X,
drivePickup2X, pickup2X, shoot2ControlX, shoot2X,
drivePickup3X, pickup3X, shoot3ControlX, shoot3X};
double[] yPoses = {startPoseY, pushBotY, shoot0ControlY, shoot0Y,
pickup1Y, openGateControlY, openGateY, shoot1ControlY, shoot1Y,
drivePickup2Y, pickup2Y, shoot2ControlY, shoot2Y,
drivePickup3Y, pickup3Y, shoot3ControlY, shoot3Y};
double[] headings = {startPoseH, pushBotH, 0, shoot0H,
pickup1H, 0, openGateH, 0, shoot1H,
drivePickup2H, pickup2H, 0, shoot2H,
drivePickup3H, pickup3H, 0, shoot3H};
Pose startPose, pushBot, shoot0Control, shoot0,
pickup1, openGateControl, openGate, shoot1Control, shoot1,
drivePickup2, pickup2, shoot2Control, shoot2,
drivePickup3, pickup3, shoot3Control, shoot3;
private void initializePoses(){
startPose = new Pose(startPoseX, startPoseY, Math.toRadians(startPoseH));
pushBot = new Pose(pushBotX, pushBotY, Math.toRadians(pushBotH));
shoot0Control = new Pose(shoot0ControlX, shoot0ControlY);
shoot0 = new Pose(shoot0X, shoot0Y, Math.toRadians(shoot0H));
pickup1 = new Pose(pickup1X, pickup1Y, Math.toRadians(pickup1H));
openGateControl = new Pose(openGateControlX, openGateControlY);
openGate = new Pose(openGateX, openGateY, Math.toRadians(openGateH));
shoot1Control = new Pose(shoot1ControlX, shoot1ControlY);
shoot1 = new Pose(shoot1X, shoot1Y, Math.toRadians(shoot1H));
drivePickup2 = new Pose(drivePickup2X, drivePickup2Y, Math.toRadians(drivePickup2H));
pickup2 = new Pose(pickup2X, pickup2Y, Math.toRadians(pickup2H));
shoot2Control = new Pose(shoot2ControlX, shoot2ControlY);
shoot2 = new Pose(shoot2X, shoot2Y, Math.toRadians(shoot2H));
drivePickup3 = new Pose(drivePickup3X, drivePickup3Y, Math.toRadians(drivePickup3H));
pickup3 = new Pose(pickup3X, pickup3Y, Math.toRadians(pickup3H));
shoot3Control = new Pose(shoot3ControlX, shoot3ControlY);
shoot3 = new Pose(shoot3X, shoot3Y, Math.toRadians(shoot3H));
startPose = new Pose(xPoses[0], yPoses[0], Math.toRadians(headings[0]));
pushBot = new Pose(xPoses[1], yPoses[1], Math.toRadians(headings[1]));
shoot0Control = new Pose(xPoses[2], yPoses[2]);
shoot0 = new Pose(xPoses[3], yPoses[3], Math.toRadians(headings[3]));
pickup1 = new Pose(xPoses[4], yPoses[4], Math.toRadians(headings[4]));
openGateControl = new Pose(xPoses[5], yPoses[5]);
openGate = new Pose(xPoses[6], yPoses[6], Math.toRadians(headings[6]));
shoot1Control = new Pose(xPoses[7], yPoses[7]);
shoot1 = new Pose(xPoses[8], yPoses[8], Math.toRadians(headings[8]));
drivePickup2 = new Pose(xPoses[9], yPoses[9], Math.toRadians(headings[9]));
pickup2 = new Pose(xPoses[10], yPoses[10], Math.toRadians(headings[10]));
shoot2Control = new Pose(xPoses[11], yPoses[11]);
shoot2 = new Pose(xPoses[12], yPoses[12], Math.toRadians(headings[12]));
drivePickup3 = new Pose(xPoses[13], yPoses[13], Math.toRadians(headings[13]));
pickup3 = new Pose(xPoses[14], yPoses[14], Math.toRadians(headings[14]));
shoot3Control = new Pose(xPoses[15], yPoses[15]);
shoot3 = new Pose(xPoses[16], yPoses[16], Math.toRadians(headings[16]));
}
//Building Paths
@@ -183,7 +193,6 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
if (!follower.isBusy() || currentTime - timeStamp > pushTime){
follower.followPath(pushBot_shoot0, true);
pathState = PathState.DRIVE_SHOOT0;
timeStamp = currentTime;
}
break;
case DRIVE_SHOOT0:
@@ -191,10 +200,12 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT0;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT0:
if (currentTime - timeStamp > rapidShootTime &&
if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
follower.followPath(shoot0_pickup1, intakePower, false);
@@ -210,6 +221,8 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
shootY = shoot1Y;
shootH = shoot1H;
timeStamp = currentTime;
shooter.setFlywheelVelocity(2300);
robot.setHoodPos(0.68);
}
break;
case OPENGATE:
@@ -261,8 +274,8 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
break;
case DRIVE_PICKUP3:
if (!follower.isBusy()){
shooter.setFlywheelVelocity(2300);
robot.setHoodPos(0.68);
shooter.setFlywheelVelocity(2200);
robot.setHoodPos(0.75);
follower.followPath(drivePickup3_pickup3, intakePower, false);
pathState = PathState.PICKUP3;
}
@@ -283,7 +296,7 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
}
break;
case WAIT_SHOOT3:
// add line here to say "done auto'
// add line here to say "done auto"
break;
default:
break;
@@ -292,7 +305,7 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
}
// Used for changing alliance
private double adjustXPoseBasedOnAlliance(double pose) {return (144-pose);}
private double adjustXPoseBasedOnAlliance(double pose) {return -pose;}
private double adjustHeadingBasedOnAlliance(double heading){
heading = 180 - heading;
while (heading > 180) {heading-=360;}
@@ -311,7 +324,7 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
follower = Constants.createFollower(hardwareMap);
sleep(1000);
follower.setStartingPose(new Pose(72,72,0));
follower.setStartingPose(new Pose(0,0,0));
loopTimes = new MeasuringLoopTimes();
loopTimes.init();
turret = new Turret(robot);
@@ -334,20 +347,15 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
if (gamepad1.crossWasPressed() && !initializeRobot){
Color.redAlliance = !Color.redAlliance;
shooter.setRedAlliance(Color.redAlliance);
}
double[] xPoses = {startPoseX, pushBotX, shoot0ControlX, shoot0X,
pickup1X, openGateControlX, openGateX, shoot1ControlX, shoot1X,
drivePickup2X, pickup2X, shoot2ControlX, shoot2X,
drivePickup3X, pickup3X, shoot3ControlX, shoot3X};
double[] headings = {startPoseH, pushBotH, shoot0H,
pickup1H, openGateH, shoot1H,
drivePickup2H, pickup2H, shoot2H,
drivePickup3H, pickup3H, shoot3H};
if (!initializeRobot){
if ((Color.redAlliance && xPoses[0] < 0)
|| (!Color.redAlliance && xPoses[0] > 0)){
for (int i = 0; i < xPoses.length; i++) {xPoses[i] = adjustXPoseBasedOnAlliance(xPoses[i]);}
for (int i = 0; i < headings.length; i++) {headings[i] = adjustHeadingBasedOnAlliance(headings[i]);}
}
}
if (gamepad1.triangleWasPressed()){
initializeRobot = true;
@@ -382,15 +390,17 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
if (isStopRequested()) return;
while (opModeIsActive()){
robot.setRapidFireBlockerPos(ServoPositions.rapidFireBlocker_Closed);
park.unpark();
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
shooter.update(robot.voltage.getVoltage());
if (!isStopRequested()){
follower.update();
}
pathStateMachine();
Pose currentPose = follower.getPose();
teleStartPoseX = currentPose.getX();
teleStartPoseY = currentPose.getY();
teleStartPoseH = Math.toDegrees(currentPose.getHeading());
TeleopV4.teleStart = follower.getPose();
spindexer.update();
@@ -402,9 +412,9 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
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.addData("X:", TeleopV4.teleStart.getX());
TELE.addData("Y:", TeleopV4.teleStart.getY());
TELE.addData("H:", TeleopV4.teleStart.getHeading());
TELE.update();
}
}

View File

@@ -0,0 +1,361 @@
package org.firstinspires.ftc.teamcode.autonomous;
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.pedropathing.follower.Follower;
import com.pedropathing.geometry.BezierCurve;
import com.pedropathing.geometry.BezierLine;
import com.pedropathing.geometry.Pose;
import com.pedropathing.paths.PathChain;
import com.qualcomm.hardware.lynx.LynxModule;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.teleop.TeleopV4;
import org.firstinspires.ftc.teamcode.utilsv2.*;
import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes;
import java.util.List;
@Config
@Autonomous (preselectTeleOp = "TeleopV4")
public class Auto15Ball_Back extends LinearOpMode {
Robot robot;
MultipleTelemetry TELE;
Follower follower;
MeasuringLoopTimes loopTimes;
Shooter shooter;
Turret turret;
Flywheel flywheel;
VelocityCommander commander;
SpindexerTransferIntake spindexer;
// Wait Times
public static double rapidWaitTime = 0.5;
public static double rapidShootTime = 0.8;
public static double loadPickupTime = 3;
// Initialize path state machine
private enum PathState {
WAIT_VELOCITY, WAIT_SHOOT0,
PICKUP3, DRIVE_SHOOT3, WAIT_SHOOT3,
PICKUP_LOAD, DRIVE_SHOOT_LOAD, WAIT_SHOOT_LOAD,
INTAKE_GATE, DRIVE_SHOOT_GATE, WAIT_SHOOT_GATE, LEAVE
}
PathState pathState = PathState.WAIT_VELOCITY;
// Poses
public static double startPoseX = 12, startPoseY = -64, startPoseH = 90;
public static double pickup3ControlX = 12, pickup3ControlY = -37;
public static double pickup3X = 61, pickup3Y = -37, pickup3H = 0;
public static double shoot3X = 16, shoot3Y = -57, shoot3H = 0;
public static double pickupLoadControlX = 21.23654066437572, pickupLoadControlY = -62.311626575028637;
public static double pickupLoadX = 63, pickupLoadY = -63, pickupLoadH = 0;
public static double shootLoadControlX = 21.23654066437572, shootLoadControlY = -62.311626575028637;
public static double shootLoadX = 16, shootLoadY = -57, shootLoadH = 0;
public static double intakeGateControl1X = 51.9656357388316, intakeGateControl1Y = -65.506277205040073;
public static double intakeGateControl2X = 60.13459335624285, intakeGateControl2Y = -67.300458190148911;
public static double intakeGateX = 59, intakeGateY = -12, intakeGateH = 90;
public static double shootGateControlX = 53.8705612829324, shootGateControlY = -35.14501718213059;
public static double shootGateX = 16, shootGateY = -57, shootGateH = 0;
public static double leaveX = 40, leaveY = 14, leaveH = 0;
double[] xPoses = {startPoseX, pickup3ControlX, pickup3X, shoot3X,
pickupLoadControlX, pickupLoadX, shootLoadControlX, shootLoadX,
intakeGateControl1X, intakeGateControl2X, intakeGateX, shootGateControlX, shootGateX, leaveX};
double[] yPoses = {startPoseY, pickup3ControlY, pickup3Y, shoot3Y,
pickupLoadControlY, pickupLoadY, shootLoadControlY, shootLoadY,
intakeGateControl1Y, intakeGateControl2Y, intakeGateY, shootGateControlY, shootGateY, leaveY};
double[] headings = {startPoseH, 0, pickup3H, shoot3H,
0, pickupLoadH, 0, shootLoadH,
0, 0, intakeGateH, 0, shootGateH, leaveH};
Pose startPose, pickup3Control, pickup3, shoot3,
pickupLoadControl, pickupLoad, shootLoadControl, shootLoad,
intakeGateControl1, intakeGateControl2, intakeGate, shootGateControl, shootGate, leave;
private void initializePoses(){
startPose = new Pose(xPoses[0], yPoses[0], Math.toRadians(headings[0]));
pickup3Control = new Pose(xPoses[1], yPoses[1]);
pickup3 = new Pose(xPoses[2], yPoses[2], Math.toRadians(headings[2]));
shoot3 = new Pose(xPoses[3], yPoses[3], Math.toRadians(headings[3]));
pickupLoadControl = new Pose(xPoses[4], yPoses[4]);
pickupLoad = new Pose(xPoses[5], yPoses[5], Math.toRadians(headings[5]));
shootLoadControl = new Pose(xPoses[6], yPoses[6]);
shootLoad = new Pose(xPoses[7], yPoses[7], Math.toRadians(headings[7]));
intakeGateControl1 = new Pose(xPoses[8], yPoses[8]);
intakeGateControl2 = new Pose(xPoses[9], yPoses[9]);
intakeGate = new Pose(xPoses[10], yPoses[10], Math.toRadians(headings[10]));
shootGateControl = new Pose(xPoses[11], yPoses[11]);
shootGate = new Pose(xPoses[12], yPoses[12], Math.toRadians(headings[12]));
leave = new Pose(xPoses[13], yPoses[13], Math.toRadians(headings[13]));
}
//Building Paths
PathChain startPose_pickup3, pickup3_shoot3, shoot3_pickupLoad, pickupLoad_shootLoad,
shootLoad_intakeGate, intakeGate_shootGate, shootGate_intakeGate, shootGate_leave;
private void buildPaths(){
startPose_pickup3 = follower.pathBuilder()
.addPath(new BezierCurve(startPose, pickup3Control, pickup3))
.setTangentHeadingInterpolation()
.build();
pickup3_shoot3 = follower.pathBuilder()
.addPath(new BezierLine(pickup3, shoot3))
.setLinearHeadingInterpolation(pickup3.getHeading(), shoot3.getHeading())
.build();
shoot3_pickupLoad = follower.pathBuilder()
.addPath(new BezierCurve(shoot3, pickupLoadControl, pickupLoad))
.setLinearHeadingInterpolation(shoot3.getHeading(), pickupLoad.getHeading())
.build();
pickupLoad_shootLoad = follower.pathBuilder()
.addPath(new BezierCurve(pickupLoad, shootLoadControl, shootLoad))
.setLinearHeadingInterpolation(pickupLoad.getHeading(), shootLoad.getHeading())
.build();
shootLoad_intakeGate = follower.pathBuilder()
.addPath(new BezierCurve(shootLoad, intakeGateControl1, intakeGateControl2, intakeGate))
.setTangentHeadingInterpolation()
.build();
intakeGate_shootGate = follower.pathBuilder()
.addPath(new BezierCurve(intakeGate, shootGateControl, shootGate))
.setLinearHeadingInterpolation(intakeGate.getHeading(), shootGate.getHeading())
.build();
shootGate_intakeGate = follower.pathBuilder()
.addPath(new BezierCurve(shootGate, intakeGateControl1, intakeGateControl2, intakeGate))
.setTangentHeadingInterpolation()
.build();
shootGate_leave = follower.pathBuilder()
.addPath(new BezierLine(shootGate, leave))
.setLinearHeadingInterpolation(shootGate.getHeading(), leave.getHeading())
.build();
}
//Path State Machine
private int startAuto = 0;
private double timeStamp = 0;
private void pathStateMachine(){
double currentTime = (double) System.currentTimeMillis() / 1000;
switch(pathState){
case WAIT_VELOCITY:
spindexer.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
shooter.setFlywheelVelocity(2400);
robot.setHoodPos(0.64);
if (flywheel.getSteady()){
startAuto++;
}
if (startAuto > 5){
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT0;
}
break;
case WAIT_SHOOT0:
if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
follower.followPath(startPose_pickup3, false);
pathState = PathState.PICKUP3;
}
break;
case PICKUP3:
if (!follower.isBusy()){
follower.followPath(pickup3_shoot3, false);
pathState = PathState.DRIVE_SHOOT3;
timeStamp = currentTime;
}
break;
case DRIVE_SHOOT3:
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTime){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT3;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT3:
if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
follower.followPath(shoot3_pickupLoad, false);
pathState = PathState.PICKUP_LOAD;
timeStamp = currentTime;
}
break;
case PICKUP_LOAD:
if (currentTime - timeStamp > loadPickupTime){
follower.followPath(pickupLoad_shootLoad, false);
pathState = PathState.DRIVE_SHOOT_LOAD;
timeStamp = currentTime;
}
break;
case DRIVE_SHOOT_LOAD:
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTime){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT_LOAD;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT_LOAD:
if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
follower.followPath(shootLoad_intakeGate, false);
pathState = PathState.INTAKE_GATE;
timeStamp = currentTime;
}
break;
case INTAKE_GATE:
if (!follower.isBusy()){
follower.followPath(intakeGate_shootGate, false);
pathState = PathState.DRIVE_SHOOT_GATE;
timeStamp = currentTime;
}
break;
case DRIVE_SHOOT_GATE:
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTime){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT_GATE;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT_GATE:
if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
follower.followPath(shootGate_intakeGate, false);
pathState = PathState.INTAKE_GATE;
timeStamp = currentTime;
// TODO: add logic for leave
}
break;
case LEAVE:
// add line here to say "done auto"
break;
default:
break;
}
TELE.update(); // use for debugging
}
// Used for changing alliance
private double adjustXPoseBasedOnAlliance(double pose) {return -pose;}
private double adjustHeadingBasedOnAlliance(double heading){
heading = 180 - heading;
while (heading > 180) {heading-=360;}
while (heading <= -180) {heading+=360;}
return heading;
}
@Override
public void runOpMode() throws InterruptedException {
Robot.resetInstance();
robot = Robot.getInstance(hardwareMap);
List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
for (LynxModule hub : allHubs) {
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
}
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
follower = Constants.createFollower(hardwareMap);
sleep(1000);
follower.setStartingPose(new Pose(0,0,0));
loopTimes = new MeasuringLoopTimes();
loopTimes.init();
turret = new Turret(robot);
flywheel = new Flywheel(robot);
commander = new VelocityCommander();
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
spindexer = new SpindexerTransferIntake(robot, TELE, commander);
ParkTilter park = new ParkTilter(robot);
boolean initializeRobot = false;
while (opModeInInit()){
park.unpark();
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
follower.update();
if (gamepad1.squareWasPressed()){
robot.setSpinPos(ServoPositions.spindexer_A2);
robot.setRapidFireBlockerPos(ServoPositions.rapidFireBlocker_Closed);
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
}
if (gamepad1.crossWasPressed() && !initializeRobot){
Color.redAlliance = !Color.redAlliance;
shooter.setRedAlliance(Color.redAlliance);
}
if (!initializeRobot){
if ((Color.redAlliance && xPoses[0] < 0)
|| (!Color.redAlliance && xPoses[0] > 0)){
for (int i = 0; i < xPoses.length; i++) {xPoses[i] = adjustXPoseBasedOnAlliance(xPoses[i]);}
for (int i = 0; i < headings.length; i++) {headings[i] = adjustHeadingBasedOnAlliance(headings[i]);}
}
}
if (gamepad1.triangleWasPressed()){
initializeRobot = true;
initializePoses();
follower.setPose(startPose);
buildPaths();
sleep(2000);
turret.switchPipeline(Turret.PipelineMode.TRACKING);
robot.limelight.start();
limelightUsed = true;
park.unpark();
}
TELE.addData("Red Alliance?", Color.redAlliance);
TELE.addData("Initialized Robot? (Don't change this until alliance is selected)", initializeRobot);
TELE.addData("Start Pose", follower.getPose());
TELE.addData("Current LL Pipeline", turret.pipeline());
TELE.update();
}
waitForStart();
if (isStopRequested()) return;
while (opModeIsActive()){
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
shooter.update(robot.voltage.getVoltage());
if (!isStopRequested()){
follower.update();
}
pathStateMachine();
TeleopV4.teleStart = follower.getPose();
spindexer.update();
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:", TeleopV4.teleStart.getX());
TELE.addData("Y:", TeleopV4.teleStart.getY());
TELE.addData("H:", TeleopV4.teleStart.getHeading());
TELE.update();
}
}
}

View File

@@ -0,0 +1,462 @@
package org.firstinspires.ftc.teamcode.autonomous;
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.pedropathing.follower.Follower;
import com.pedropathing.geometry.BezierCurve;
import com.pedropathing.geometry.BezierLine;
import com.pedropathing.geometry.Pose;
import com.pedropathing.paths.PathChain;
import com.qualcomm.hardware.lynx.LynxModule;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.teleop.TeleopV4;
import org.firstinspires.ftc.teamcode.utilsv2.*;
import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes;
import java.util.List;
@Config
@Autonomous (preselectTeleOp = "TeleopV4")
public class Auto21Ball_Front_Gate extends LinearOpMode {
Robot robot;
MultipleTelemetry TELE;
Follower follower;
MeasuringLoopTimes loopTimes;
Shooter shooter;
Turret turret;
Flywheel flywheel;
VelocityCommander commander;
SpindexerTransferIntake spindexer;
double runtime = 0;
// Wait Times
public static double rapidWaitTime = 0.4;
public static double rapidShootTime = 0.45;
public static double openGate1Time = 1.5;
public static double openGate2Time = 1.5;
public static double openGateWaitTimeMax = 3;
public static double openGateWaitTimeMin = 1.75;
public static int maxLoopCycles = 3;
// Initialize path state machine
private enum PathState {
DRIVE_SHOOT0, WAIT_SHOOT0,
PICKUP1, OPENGATE1, DRIVE_SHOOT1, WAIT_SHOOT1,
PICKUP2, OPENGATE2, DRIVE_SHOOT2, WAIT_SHOOT2,
INTAKE_GATE, DRIVE_SHOOT_GATE, WAIT_SHOOT_GATE, DRIVE_SHOOT_LEAVE, WAIT_SHOOT_LEAVE
}
PathState pathState = PathState.DRIVE_SHOOT0;
// Poses
public static double startPoseX = 55, startPoseY = 39, startPoseH = 0;
public static double shoot0X = 25, shoot0Y = 18, shoot0H = 0;
public static double pickup1ControlX = 29.53321878579611, pickup1ControlY = 9.84077892325314;
public static double pickup1X = 50, pickup1Y = 10, pickup1H = 0;
public static double openGate1ControlX = 43.82989690721648, openGate1ControlY = 3.86540664375714;
public static double openGate1X = 59, openGate1Y = 2, openGate1H = 0;
public static double shoot1ControlX = 40, shoot1ControlY = 3;
public static double shoot1X = 25, shoot1Y = 11, shoot1H = -30;
public static double pickup2ControlX = 18, pickup2ControlY = -18;
public static double pickup2X = 61, pickup2Y = -14.5, pickup2H = 0;
public static double openGate2ControlX = 45.9782359679267, openGate2ControlY = -15.106643757159245;
public static double openGate2X = 57, openGate2Y = -8, openGate2H = 0;
public static double shoot2ControlX = 57, shoot2ControlY = -8;
public static double shoot2X = 25, shoot2Y = 11, shoot2H = -30;
public static double intakeGateControlX = 61, intakeGateControlY = -11;
public static double intakeGateX = 61, intakeGateY = -11, intakeGateH = 20;
public static double shootGateControlX = 56, shootGateControlY = -10;
public static double shootGateX = 25, shootGateY = 11, shootGateH = -30;
public static double shootLeaveControlX = 56, shootLeaveControlY = -10;
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,
pickup1ControlX, pickup1X, openGate1ControlX, openGate1X, shoot1ControlX, shoot1X,
pickup2ControlX, pickup2X, openGate2ControlX, openGate2X, shoot2ControlX, shoot2X,
intakeGateControlX, intakeGateX, shootGateControlX, shootGateX,
shootLeaveControlX, shootLeaveX, leaveX, awayFromGateX};
double[] yPoses = {startPoseY, shoot0Y,
pickup1ControlY, pickup1Y, openGate1ControlY, openGate1Y, shoot1ControlY, shoot1Y,
pickup2ControlY, pickup2Y, openGate2ControlY, openGate2Y, shoot2ControlY, shoot2Y,
intakeGateControlY, intakeGateY, shootGateControlY, shootGateY,
shootLeaveControlY, shootLeaveY, leaveY, awayFromGateY};
double[] headings = {startPoseH, shoot0H,
0, pickup1H, 0, openGate1H, 0, shoot1H,
0, pickup2H, 0, openGate2H, 0, shoot2H,
0, intakeGateH, 0, shootGateH,
0, shootLeaveH, leaveH, awayFromGateH};
Pose startPose, shoot0,
pickup1Control, pickup1, openGate1Control, openGate1, shoot1Control, shoot1,
pickup2Control, pickup2, openGate2Control, openGate2, shoot2Control, shoot2,
intakeGateControl, intakeGate, shootGateControl, shootGate,
shootLeaveControl, shootLeave, leave, awayFromGate;
private void initializePoses(){
startPose = new Pose(xPoses[0], yPoses[0], Math.toRadians(headings[0]));
shoot0 = new Pose(xPoses[1], yPoses[1], Math.toRadians(headings[1]));
pickup1Control = new Pose(xPoses[2], yPoses[2]);
pickup1 = new Pose(xPoses[3], yPoses[3], Math.toRadians(headings[3]));
openGate1Control = new Pose(xPoses[4], yPoses[4]);
openGate1 = new Pose(xPoses[5], yPoses[5], Math.toRadians(headings[5]));
shoot1Control = new Pose(xPoses[6], yPoses[6]);
shoot1 = new Pose(xPoses[7], yPoses[7], Math.toRadians(headings[7]));
pickup2Control = new Pose(xPoses[8], yPoses[8]);
pickup2 = new Pose(xPoses[9], yPoses[9], Math.toRadians(headings[9]));
openGate2Control = new Pose(xPoses[10], yPoses[10]);
openGate2 = new Pose(xPoses[11], yPoses[11], Math.toRadians(headings[11]));
shoot2Control = new Pose(xPoses[12], yPoses[12]);
shoot2 = new Pose(xPoses[13], yPoses[13], Math.toRadians(headings[13]));
intakeGateControl = new Pose(xPoses[14], yPoses[14]);
intakeGate = new Pose(xPoses[15], yPoses[15], Math.toRadians(headings[15]));
shootGateControl = new Pose(xPoses[16], yPoses[16]);
shootGate = new Pose(xPoses[17], yPoses[17], Math.toRadians(headings[17]));
shootLeaveControl = new Pose(xPoses[18], yPoses[18]);
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
PathChain startPose_shoot0, shoot0_pickup1, pickup1_openGate1, openGate1_shoot1,
shoot1_pickup2, pickup2_openGate2, openGate2_shoot2,
shoot2_intakeGate, intakeGate_shootGate, shootGate_intakeGate, intakeGate_shootLeave, shootGate_leave, intakeGate_awayFromGate;
private void buildPaths(){
startPose_shoot0 = follower.pathBuilder()
.addPath(new BezierLine(startPose, shoot0))
.setLinearHeadingInterpolation(startPose.getHeading(), shoot0.getHeading())
.build();
shoot0_pickup1 = follower.pathBuilder()
.addPath(new BezierCurve(shoot0, pickup1Control, pickup1))
.setLinearHeadingInterpolation(shoot0.getHeading(), pickup1.getHeading())
.build();
pickup1_openGate1 = follower.pathBuilder()
.addPath(new BezierCurve(pickup1, openGate1Control, openGate1))
.setLinearHeadingInterpolation(pickup1.getHeading(), openGate1.getHeading())
.build();
openGate1_shoot1 = follower.pathBuilder()
.addPath(new BezierCurve(openGate1, shoot1Control, shoot1))
.setLinearHeadingInterpolation(openGate1.getHeading(), shoot1.getHeading())
.build();
shoot1_pickup2 = follower.pathBuilder()
.addPath(new BezierCurve(shoot1, pickup2Control, pickup2))
.setLinearHeadingInterpolation(shoot1.getHeading(), pickup2.getHeading())
.build();
pickup2_openGate2 = follower.pathBuilder()
.addPath(new BezierCurve(pickup2, openGate2Control, openGate2))
.setLinearHeadingInterpolation(pickup2.getHeading(), openGate2.getHeading())
.build();
openGate2_shoot2 = follower.pathBuilder()
.addPath(new BezierCurve(openGate2, shoot2Control, shoot2))
.setLinearHeadingInterpolation(openGate2.getHeading(), shoot2.getHeading())
.build();
shoot2_intakeGate = follower.pathBuilder()
.addPath(new BezierCurve(shoot2, intakeGateControl, intakeGate))
.setLinearHeadingInterpolation(shoot2.getHeading(), intakeGate.getHeading())
.build();
intakeGate_shootGate = follower.pathBuilder()
.addPath(new BezierCurve(intakeGate, shootGateControl, shootGate))
.setLinearHeadingInterpolation(intakeGate.getHeading(), shootGate.getHeading())
.build();
shootGate_intakeGate = follower.pathBuilder()
.addPath(new BezierCurve(shootGate, intakeGateControl, intakeGate))
.setLinearHeadingInterpolation(shootGate.getHeading(), intakeGate.getHeading())
.build();
intakeGate_shootLeave = follower.pathBuilder()
.addPath(new BezierCurve(intakeGate, shootLeaveControl, shootLeave))
.setLinearHeadingInterpolation(intakeGate.getHeading(), shootLeave.getHeading())
.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
private boolean startAuto = true;
private double timeStamp = 0;
private int cycle = 0;
private void pathStateMachine(){
double currentTime = (double) System.currentTimeMillis() / 1000;
switch(pathState){
case DRIVE_SHOOT0:
spindexer.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
shooter.setFlywheelVelocity(2300);
robot.setHoodPos(0.68);
if (startAuto){
follower.followPath(startPose_shoot0, false);
startAuto = false;
}
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTime){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT0;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT0:
if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
follower.followPath(shoot0_pickup1, false);
pathState = PathState.PICKUP1;
}
break;
case PICKUP1:
if (!follower.isBusy()){
follower.followPath(pickup1_openGate1, false);
pathState = PathState.OPENGATE1;
timeStamp = currentTime;
}
break;
case OPENGATE1:
if (currentTime - timeStamp > openGate1Time){
follower.followPath(openGate1_shoot1, false);
pathState = PathState.DRIVE_SHOOT1;
timeStamp = currentTime;
}
break;
case DRIVE_SHOOT1:
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTime){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT1;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT1:
if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
follower.followPath(shoot1_pickup2, false);
pathState = PathState.PICKUP2;
}
break;
case PICKUP2:
if (!follower.isBusy()){
follower.followPath(pickup2_openGate2, false);
pathState = PathState.OPENGATE2;
timeStamp = currentTime;
}
break;
case OPENGATE2:
if (currentTime - timeStamp > openGate2Time){
follower.followPath(openGate2_shoot2, false);
pathState = PathState.DRIVE_SHOOT2;
timeStamp = currentTime;
}
break;
case DRIVE_SHOOT2:
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTime){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT2;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT2:
if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
follower.followPath(shoot2_intakeGate, false);
pathState = PathState.INTAKE_GATE;
timeStamp = currentTime;
}
break;
case INTAKE_GATE:
if ((currentTime - timeStamp > openGateWaitTimeMax || (robot.insideBeam.isPressed() && robot.outsideBeam.isPressed()))
&& (currentTime - timeStamp > openGateWaitTimeMin)){
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;
}
// TODO: add logic to shoot gate
break;
case DRIVE_SHOOT_GATE:
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTime){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT_GATE;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT_GATE:
if (currentTime - timeStamp > rapidShootTime ||
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
cycle++;
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;
}
break;
case DRIVE_SHOOT_LEAVE:
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTime){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT_LEAVE;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
} else if (follower.isBusy()){
timeStamp = currentTime;
}
break;
case WAIT_SHOOT_LEAVE:
// add line here to say "done auto"
break;
default:
break;
}
TELE.addData("Moving?", follower.isBusy());
}
// Used for changing alliance
private double adjustXPoseBasedOnAlliance(double pose) {return -pose;}
private double adjustHeadingBasedOnAlliance(double heading){
heading = 180 - heading;
while (heading > 180) {heading-=360;}
while (heading <= -180) {heading+=360;}
return heading;
}
@Override
public void runOpMode() throws InterruptedException {
Robot.resetInstance();
robot = Robot.getInstance(hardwareMap);
List<LynxModule> allHubs = hardwareMap.getAll(LynxModule.class);
for (LynxModule hub : allHubs) {
hub.setBulkCachingMode(LynxModule.BulkCachingMode.MANUAL);
}
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
follower = Constants.createFollower(hardwareMap);
sleep(1000);
follower.setStartingPose(new Pose(0,0,0));
loopTimes = new MeasuringLoopTimes();
loopTimes.init();
turret = new Turret(robot);
flywheel = new Flywheel(robot);
commander = new VelocityCommander();
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
spindexer = new SpindexerTransferIntake(robot, TELE, commander);
ParkTilter park = new ParkTilter(robot);
boolean startAuto = true;
boolean initializeRobot = false;
while (opModeInInit()){
follower.update();
if (gamepad1.squareWasPressed()){
robot.setSpinPos(ServoPositions.spindexer_A2);
robot.setRapidFireBlockerPos(ServoPositions.rapidFireBlocker_Closed);
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
}
if (gamepad1.crossWasPressed() && !initializeRobot){
Color.redAlliance = !Color.redAlliance;
shooter.setRedAlliance(Color.redAlliance);
}
if (!initializeRobot){
if ((Color.redAlliance && xPoses[0] < 0)
|| (!Color.redAlliance && xPoses[0] > 0)){
for (int i = 0; i < xPoses.length; i++) {xPoses[i] = adjustXPoseBasedOnAlliance(xPoses[i]);}
for (int i = 0; i < headings.length; i++) {headings[i] = adjustHeadingBasedOnAlliance(headings[i]);}
}
}
if (gamepad1.triangleWasPressed()){
initializeRobot = true;
initializePoses();
follower.setPose(startPose);
buildPaths();
sleep(2000);
turret.switchPipeline(Turret.PipelineMode.TRACKING);
robot.limelight.start();
limelightUsed = true;
park.unpark();
}
TELE.addData("Red Alliance?", Color.redAlliance);
TELE.addData("Initialized Robot? (Don't change this until alliance is selected)", initializeRobot);
TELE.addData("Start Pose", follower.getPose());
TELE.addData("Current LL Pipeline", turret.pipeline());
TELE.update();
}
waitForStart();
if (isStopRequested()) return;
while (opModeIsActive()){
if (startAuto){
runtime = getRuntime();
startAuto = false;
}
park.unpark();
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
shooter.update(robot.voltage.getVoltage());
if (!isStopRequested()){
follower.update();
}
pathStateMachine();
TeleopV4.teleStart = follower.getPose();
spindexer.update();
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:", TeleopV4.teleStart.getX());
TELE.addData("Y:", TeleopV4.teleStart.getY());
TELE.addData("H:", TeleopV4.teleStart.getHeading());
TELE.update();
}
}
}

View File

@@ -42,8 +42,8 @@ public class Constants {
public static PathConstraints pathConstraints = new PathConstraints(0.99, 100, breakingStrength, 1);
public static PinpointConstants localizerConstants = new PinpointConstants()
.forwardPodY(3.7795)
.strafePodX(-3.676)
.forwardPodY(-3.7795)
.strafePodX(-3.769)
.distanceUnit(DistanceUnit.INCH)
.hardwareMapName("pinpoint")
.encoderResolution(GoBildaPinpointDriver.GoBildaOdometryPods.goBILDA_4_BAR_POD)

View File

@@ -148,7 +148,7 @@ class LocalizationTest extends OpMode {
@Override
public void init() {
follower.setStartingPose(new Pose(72,72, 0));
follower.setStartingPose(new Pose(0,0, 0));
}
/** This initializes the PoseUpdater, the drive motors, and the Panels telemetry. */
@@ -1272,7 +1272,7 @@ class CentripetalTuner extends OpMode {
public void start() {
follower.activateAllPIDFs();
forwards = new Path(new BezierCurve(new Pose(0,0), new Pose(Math.abs(DISTANCE) ,0), new Pose(Math.abs(DISTANCE) ,DISTANCE )));
backwards = new Path(new BezierCurve(new Pose(Math.abs(DISTANCE) + 72,DISTANCE + 72), new Pose(Math.abs(DISTANCE) ,0), new Pose(0,0)));
backwards = new Path(new BezierCurve(new Pose(Math.abs(DISTANCE) + 0,DISTANCE + 0), new Pose(Math.abs(DISTANCE) ,0), new Pose(0,0)));
backwards.setTangentHeadingInterpolation();
backwards.reverseHeadingInterpolation();
@@ -1382,14 +1382,14 @@ class Circle extends OpMode {
public void start() {
circle = follower.pathBuilder()
.addPath(new BezierCurve(new Pose(72, 72), new Pose(RADIUS + 72, 72), new Pose(RADIUS + 72, RADIUS + 72)))
.setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72))
.addPath(new BezierCurve(new Pose(RADIUS + 72, RADIUS + 72), new Pose(RADIUS + 72, (2 * RADIUS) + 72), new Pose(72, (2 * RADIUS) + 72)))
.setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72))
.addPath(new BezierCurve(new Pose(72, (2 * RADIUS) + 72), new Pose(-RADIUS + 72, (2 * RADIUS) + 72), new Pose(-RADIUS + 72, RADIUS + 72)))
.setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72))
.addPath(new BezierCurve(new Pose(-RADIUS + 72, RADIUS + 72), new Pose(-RADIUS + 72, 72), new Pose(72, 72)))
.setHeadingInterpolation(HeadingInterpolator.facingPoint(72, RADIUS + 72))
.addPath(new BezierCurve(new Pose(0, 0), new Pose(RADIUS + 0, 0), new Pose(RADIUS + 0, RADIUS + 0)))
.setHeadingInterpolation(HeadingInterpolator.facingPoint(0, RADIUS + 0))
.addPath(new BezierCurve(new Pose(RADIUS + 0, RADIUS + 0), new Pose(RADIUS + 0, (2 * RADIUS) + 0), new Pose(0, (2 * RADIUS) + 0)))
.setHeadingInterpolation(HeadingInterpolator.facingPoint(0, RADIUS + 0))
.addPath(new BezierCurve(new Pose(0, (2 * RADIUS) + 0), new Pose(-RADIUS + 0, (2 * RADIUS) + 0), new Pose(-RADIUS + 0, RADIUS + 0)))
.setHeadingInterpolation(HeadingInterpolator.facingPoint(0, RADIUS + 0))
.addPath(new BezierCurve(new Pose(-RADIUS + 0, RADIUS + 0), new Pose(-RADIUS + 0, 0), new Pose(0, 0)))
.setHeadingInterpolation(HeadingInterpolator.facingPoint(0, RADIUS + 0))
.build();
follower.followPath(circle);
}
@@ -1406,7 +1406,7 @@ class Circle extends OpMode {
@Override
public void init() {
follower.setStartingPose(new Pose(72, 72));
follower.setStartingPose(new Pose(0, 0));
}
/**
@@ -1639,8 +1639,8 @@ class OffsetsTuner extends OpMode {
telemetry.addLine("Total Angle: " + follower.getTotalHeading());
telemetry.addLine("The following values are the offsets in inches that should be applied to your localizer.");
telemetry.addLine("strafeX: " + ((72.0-follower.getPose().getX()) / 2.0));
telemetry.addLine("forwardY: " + ((72.0-follower.getPose().getY()) / 2.0));
telemetry.addLine("strafeX: " + ((0.0-follower.getPose().getX()) / 2.0));
telemetry.addLine("forwardY: " + ((0.0-follower.getPose().getY()) / 2.0));
telemetry.update();
drawCurrentAndHistory();

View File

@@ -1,9 +1,5 @@
package org.firstinspires.ftc.teamcode.teleop;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseH;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseX;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseY;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
@@ -34,7 +30,12 @@ public class TeleopV4 extends LinearOpMode {
ParkTilter parkTilter;
MeasuringLoopTimes loopTimes;
public static Pose relocalizePose = new Pose(128, 83, 0);
public static Pose relocalizePose = new Pose(56, 11, 0);
public static Pose teleStart = new Pose(0,0,0);
private boolean firstTickFull = true;
private boolean intakeFull = true;
private boolean shooting = false;
@Override
public void runOpMode() throws InterruptedException {
@@ -50,8 +51,10 @@ public class TeleopV4 extends LinearOpMode {
commander = new VelocityCommander();
drivetrain = new Drivetrain(robot, TELE);
follower = Constants.createFollower(hardwareMap);
Pose start = new Pose(teleStartPoseX, teleStartPoseY, Math.toRadians(teleStartPoseH));
follower.setStartingPose(start);
follower.setStartingPose(teleStart);
sleep(500);
follower.setPose(teleStart);
follower.update();
flywheel = new Flywheel(robot);
turret = new Turret(robot);
@@ -73,20 +76,52 @@ public class TeleopV4 extends LinearOpMode {
limelightUsed = true;
TELE.addLine("Initialization is done");
TELE.addData("Starting Position", follower.getPose());
TELE.addData("TELE START", teleStart);
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();
if (isStopRequested()) return;
int emptyTicks = 0;
while (opModeIsActive()) {
//Drivetrain
drivetrain.drive(
-gamepad1.right_stick_y,
gamepad1.right_stick_x,
gamepad1.left_stick_x
gamepad1.left_stick_x,
gamepad1.left_trigger
);
if (gamepad1.crossWasPressed()){
if (Color.redAlliance){
relocalizePose = new Pose(57.5, 5, 0);
} else {
relocalizePose = new Pose(-57.5, 5, Math.toRadians(180));
}
follower.setPose(relocalizePose);
sleep(500);
gamepad1.rumble(100);
}
@@ -104,7 +139,23 @@ public class TeleopV4 extends LinearOpMode {
if (shooter.getState() == Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR || shooter.getState() == Shooter.ShooterState.MANUAL){
shooter.setFlywheelVelocity(2500);
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());
@@ -121,6 +172,25 @@ public class TeleopV4 extends LinearOpMode {
state == SpindexerTransferIntake.RapidMode.HOLD_BALLS)) {
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 &&
@@ -134,6 +204,7 @@ public class TeleopV4 extends LinearOpMode {
if (gamepad1.right_bumper && state != SpindexerTransferIntake.RapidMode.OPEN_GATE && state != SpindexerTransferIntake.RapidMode.SHOOT) {
robot.setIntakePower(1);
robot.setTransferPower(-0.7);
}
if (gamepad2.leftBumperWasPressed()){
@@ -149,20 +220,20 @@ public class TeleopV4 extends LinearOpMode {
}
loopTimes.loop();
TELE.addData("Loop Time Average", loopTimes.getAvgLoopTime());
TELE.addData("Loop Time Max", loopTimes.getMaxLoopTimeOneMin());
TELE.addData("Loop Time Min", loopTimes.getMinLoopTimeOneMin());
// TELE.addData("Loop Time Average", loopTimes.getAvgLoopTime());
// TELE.addData("Loop Time Max", loopTimes.getMaxLoopTimeOneMin());
// TELE.addData("Loop Time Min", loopTimes.getMinLoopTimeOneMin());
//
TELE.addData("Distance From Goal", commander.getDistance());
TELE.addData("Hood Position", commander.getHoodPredicted());
TELE.addData("Transfer Power", robot.transfer.getPower());
// TELE.addData("Hood Position", commander.getHoodPredicted());
// TELE.addData("Transfer Power", robot.transfer.getPower());
TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM());
TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity());
TELE.addData("Current Position", currentPose);
TELE.addData("Current LL Pipeline", turret.pipeline());
//
// TELE.addData("Current Position", currentPose);
//
// TELE.addData("Current LL Pipeline", turret.pipeline());
//
TELE.update();
}

View File

@@ -131,7 +131,7 @@ public class Hardware_Tester extends LinearOpMode {
NormalizedRGBA revColor = robot.revSensor.getNormalizedColors();
TELE.addData("REV Distance", robot.revSensor.getDistance(DistanceUnit.CM));
TELE.addData("REV Green", revColor.green / (revColor.red + revColor.blue + revColor.green));
TELE.addData("REV Green", revColor.blue / (revColor.green + revColor.blue + revColor.red));
TELE.addData("Voltage Sensor", robot.voltage.getVoltage());

View File

@@ -1,8 +1,5 @@
package org.firstinspires.ftc.teamcode.tests;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseH;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseX;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseY;
import static org.firstinspires.ftc.teamcode.utilsv2.Turret.limelightUsed;
import com.acmerobotics.dashboard.FtcDashboard;
@@ -35,7 +32,7 @@ public class NewShooterTest extends LinearOpMode {
public static int flywheelVelo = 0;
public static double hoodPos = 0.5;
public static double transferPower = -0.8;
// public static double turretPos = 0.51;
public static boolean overrideTransferPower = false;
@Override
public void runOpMode() throws InterruptedException {
@@ -51,8 +48,9 @@ public class NewShooterTest extends LinearOpMode {
commander = new VelocityCommander();
drivetrain = new Drivetrain(robot, TELE);
follower = Constants.createFollower(hardwareMap);
Pose start = new Pose(teleStartPoseX, teleStartPoseY, Math.toRadians(teleStartPoseH));
follower.setStartingPose(start);
follower.setStartingPose(new Pose(0,0,0));
sleep(500);
follower.setPose(new Pose(0,0,0));
flywheel = new Flywheel(robot);
turret = new Turret(robot);
@@ -71,6 +69,9 @@ public class NewShooterTest extends LinearOpMode {
limelightUsed = true;
TELE.addLine("Initialization Complete");
TELE.update();
waitForStart();
if (isStopRequested()) return;
@@ -80,11 +81,18 @@ public class NewShooterTest extends LinearOpMode {
drivetrain.drive(
-gamepad1.right_stick_y,
gamepad1.right_stick_x,
gamepad1.left_stick_x
gamepad1.left_stick_x,
gamepad1.left_trigger
);
if (gamepad1.crossWasPressed()){
if (Color.redAlliance){
TeleopV4.relocalizePose = new Pose(57.5, 5, 0);
} else {
TeleopV4.relocalizePose = new Pose(-57.5, 5, Math.toRadians(180));
}
follower.setPose(TeleopV4.relocalizePose);
sleep(500);
gamepad1.rumble(100);
}
@@ -101,7 +109,6 @@ public class NewShooterTest extends LinearOpMode {
if (shooter.getState() == Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR || shooter.getState() == Shooter.ShooterState.MANUAL){
shooter.setFlywheelVelocity(flywheelVelo);
robot.setHoodPos(hoodPos);
robot.setTransferPower(transferPower);
}
@@ -150,6 +157,7 @@ public class NewShooterTest extends LinearOpMode {
TELE.addData("Hood Position", commander.getHoodPredicted());
TELE.addData("Transfer Power", commander.getTransferPow());
TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM());
TELE.addData("Manuel Velocity RPM", flywheelVelo);
TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity());
TELE.addData("TX:", turret.getTX());

View File

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

View File

@@ -37,7 +37,7 @@ public class Drivetrain {
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 snappedStrafe = false;
@@ -79,18 +79,30 @@ public class Drivetrain {
robot.setFrontRightPower(frontRightPower);
robot.setBackRightPower(backRightPower);
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);
if (stop > 0.5){
robot.frontLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
robot.backLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
robot.frontRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
robot.backRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
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;
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.HardwareMap;
@@ -16,10 +18,20 @@ public class Flywheel {
// public PIDFCoefficients shooterPIDF1, shooterPIDF2;
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_I = 1;
public static double shooterPIDF_D = 0.0;
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 velo1 = 0.0;
@@ -36,6 +48,8 @@ public class Flywheel {
public Flywheel(Robot rob) {
robot = rob;
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() {
@@ -67,19 +81,23 @@ public class Flywheel {
shooterPIDF.d = d;
shooterPIDF.f = f;
// pidf.setPIDF(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, 0);
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
}
private double prevF = 0;
public static double voltagePIDFDifference = 1;
double averageVoltage = 0;
public void setF(double voltage){
averageVoltage = ALPHA * voltage + (1 - ALPHA) * averageVoltage;
double f = shooterPIDF_F / voltage;
if (Math.abs(prevF - f) > voltagePIDFDifference) {
if (Math.abs(prevF - f) > voltagePIDFDifference && !steady) {
shooterPIDF.f = f;
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
prevF = f;
}
prevF = f;
}
// Convert from RPM to Ticks per Second
@@ -92,25 +110,30 @@ public class Flywheel {
return (TPS * 60.0) / 28.0;
}
double ALPHA = 0.3;
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;
if (velocityHistory.size() > velocityHistorySize) {
velocityHistory.removeFirst();
}
double sum = 0.0;
for (double v : velocityHistory) {
sum += v;
}
averageVelocity = sum / velocityHistory.size();
averageVelocity = ALPHA * newVelocity + (1 - ALPHA) * averageVelocity;
}
double power;
double prevTargetTime = 0;
double prevTargetVelocity = 0;
public void manageFlywheel(double commandedVelocity) {
if (Math.abs(targetVelocity - commandedVelocity) > 0.0001) {
@@ -125,13 +148,12 @@ public class Flywheel {
velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
velo = (velo1 + velo2) / 2.0;
velo = velo1;
updateVelocityAverage(velo);
steady = (Math.abs(commandedVelocity - averageVelocity) < 50);
}
public double getShooterPower(){return power;}
}

View File

@@ -174,7 +174,7 @@ public class Robot {
private double prevFrontLeftPower = -10.501;
public void setFrontLeftPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
pow = (double) Math.round((float) pow * roundingFactor) / roundingFactor;
if (pow != prevFrontLeftPower){
frontLeft.setPower(pow);
}
@@ -183,7 +183,7 @@ public class Robot {
private double prevFrontRightPower = -10.501;
public void setFrontRightPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
pow = (double) Math.round((float) pow * roundingFactor) / roundingFactor;
if (pow != prevFrontRightPower){
frontRight.setPower(pow);
}
@@ -192,7 +192,7 @@ public class Robot {
private double prevBackLeftPower = -10.501;
public void setBackLeftPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
pow = (double) Math.round((float) pow * roundingFactor) / roundingFactor;
if (pow != prevBackLeftPower){
backLeft.setPower(pow);
}
@@ -201,7 +201,7 @@ public class Robot {
private double prevBackRightPower = -10.501;
public void setBackRightPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
pow = (double) Math.round((float) pow * roundingFactor) / roundingFactor;
if (pow != prevBackRightPower){
backRight.setPower(pow);
}
@@ -210,7 +210,7 @@ public class Robot {
private double prevIntakePower = -10.501;
public void setIntakePower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
pow = (double) Math.round((float) pow * roundingFactor) / roundingFactor;
if (pow != prevIntakePower){
intake.setPower(pow);
}
@@ -219,7 +219,7 @@ public class Robot {
private double prevTransferPower = -10.501;
public void setTransferPower(double pow){
pow = (double) Math.round(pow * roundingFactor) / roundingFactor;
pow = (double) Math.round((float) pow * roundingFactor) / roundingFactor;
if (pow != prevTransferPower){
transfer.setPower(pow);
}
@@ -230,7 +230,7 @@ public class Robot {
private double prevHoodPos = -10.501;
public void setHoodPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevHoodPos){
hood.setPosition(pos);
}
@@ -239,7 +239,7 @@ public class Robot {
private double prevTransferServoPos = -10.501;
public void setTransferServoPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevTransferServoPos){
transferServo.setPosition(pos);
}
@@ -248,7 +248,7 @@ public class Robot {
private double prevSpinPos = -10.501;
public void setSpinPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevSpinPos){
spin1.setPosition(pos);
spin2.setPosition(pos);
@@ -258,7 +258,7 @@ public class Robot {
private double prevTurretPos = -10.501;
public void setTurretPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevTurretPos){
turr1.setPosition(pos);
turr2.setPosition(pos);
@@ -268,7 +268,7 @@ public class Robot {
private double prevTilt1Pos = -10.501;
public void setTilt1Pos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevTilt1Pos){
tilt1.setPosition(pos);
}
@@ -277,7 +277,7 @@ public class Robot {
private double prevTilt2Pos = -10.501;
public void setTilt2Pos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevTilt2Pos){
tilt2.setPosition(pos);
}
@@ -286,7 +286,7 @@ public class Robot {
private double prevSpindexBlockerPos = -10.501;
public void setSpindexBlockerPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevSpindexBlockerPos){
spindexBlocker.setPosition(pos);
}
@@ -295,7 +295,7 @@ public class Robot {
private double prevRapidFireBlockerPos = -10.501;
public void setRapidFireBlockerPos(double pos){
pos = (double) Math.round(pos * roundingFactor) / roundingFactor;
pos = (double) Math.round((float) pos * roundingFactor) / roundingFactor;
if (pos != prevRapidFireBlockerPos){
rapidFireBlocker.setPosition(pos);
}

View File

@@ -6,6 +6,8 @@ import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.pedropathing.follower.Follower;
import org.firstinspires.ftc.teamcode.constants.Color;
@Config
public class Shooter {
@@ -42,14 +44,14 @@ public class Shooter {
this.red = input;
if (this.red) {
goalX = 144;
turretGoalX = 140;
goalX = 72;
turretGoalX = 68;
} else {
goalX = 0;
turretGoalX = 8;
goalX = -72;
turretGoalX = -68;
}
goalY = 144;
turretGoalY = 132;
goalY = 72;
turretGoalY = 68;
}
private double flywheelVelocity = 0.0;
@@ -89,7 +91,7 @@ public class Shooter {
private final double shooterDistFromCenter = 1.545;
public void update(double voltage) {
setRedAlliance(Color.redAlliance);
switch (state) {
case NOTHING:
break;
@@ -102,7 +104,8 @@ public class Shooter {
follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent(),
voltage
voltage,
fly.getAverageVelocity()
);
fly.manageFlywheel(flywheelVelocity);
@@ -129,7 +132,8 @@ public class Shooter {
follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent(),
voltage
voltage,
fly.getAverageVelocity()
);
flywheelVelocity = commander.getPredictedRPM();
@@ -151,7 +155,8 @@ public class Shooter {
follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent(),
voltage
voltage,
fly.getAverageVelocity()
);
flywheelVelocity = commander.getPredictedRPM();
@@ -170,7 +175,8 @@ public class Shooter {
follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent(),
voltage
voltage,
fly.getAverageVelocity()
);
flywheelVelocity = commander.getPredictedRPM();
@@ -198,7 +204,8 @@ public class Shooter {
follow.getAcceleration().getXComponent(),
follow.getVelocity().getYComponent(),
follow.getAcceleration().getYComponent(),
voltage
voltage,
fly.getAverageVelocity()
);
fly.manageFlywheel(flywheelVelocity);
fly.setPIDF(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / voltage);

View File

@@ -53,8 +53,8 @@ public class SpindexerTransferIntake {
}
int[] shootOrder = {0, 1, 2};
private final double sensorDistanceThreshold = 6.0;
private final long pulseTime = 100; // ms
final double sensorDistanceThreshold = 5.3;
final long pulseTime = 100; // ms
private DesiredPattern desiredPattern = DesiredPattern.GPP;
@@ -203,8 +203,8 @@ public class SpindexerTransferIntake {
private RapidMode rapidMode = RapidMode.INTAKE;
private SortedIntakeStates sortedIntakeStates = SortedIntakeStates.IDLE;
private BallStates[] ballColors = {BallStates.UNKNOWN, BallStates.UNKNOWN, BallStates.UNKNOWN};
private final double greenThresh = 0.39;
private final double spinMovementTime = 250;
final double greenThresh = 0.39;
final double spinMovementTime = 250;
/**
* Time when current state was entered.
@@ -273,22 +273,23 @@ public class SpindexerTransferIntake {
private int greenTicks = 0;
private int ballTicks = 0;
private int holdBallsTicker = 0;
public void update() {
TELE.addData("Sorted State", sortedIntakeStates);
TELE.addData("Ball0", ballColors[0]);
TELE.addData("Ball1", ballColors[1]);
TELE.addData("Ball2", ballColors[2]);
TELE.addData("Shoot0", shootOrder[0]);
TELE.addData("Shoot1", shootOrder[1]);
TELE.addData("Shoot2", shootOrder[2]);
TELE.addData("Color0", ballColors[0]);
TELE.addData("Color1", ballColors[1]);
TELE.addData("Color2", ballColors[2]);
TELE.addData("Shoot State", shootState);
// TELE.addData("Sorted State", sortedIntakeStates);
// TELE.addData("Ball0", ballColors[0]);
// TELE.addData("Ball1", ballColors[1]);
// TELE.addData("Ball2", ballColors[2]);
//
// TELE.addData("Shoot0", shootOrder[0]);
// TELE.addData("Shoot1", shootOrder[1]);
// TELE.addData("Shoot2", shootOrder[2]);
//
// TELE.addData("Color0", ballColors[0]);
// TELE.addData("Color1", ballColors[1]);
// TELE.addData("Color2", ballColors[2]);
//
// TELE.addData("Shoot State", shootState);
switch (mode) {
@@ -316,9 +317,13 @@ public class SpindexerTransferIntake {
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;
@@ -367,47 +372,54 @@ public class SpindexerTransferIntake {
if (robot.insideBeam.isPressed()
&& robot.outsideBeam.isPressed()) {
robot.setTransferPower(0);
robot.setIntakePower(0.1);
robot.setTransferServoPos(ServoPositions.transferServo_in);
} else {
holdBallsTicker++;
robot.setIntakePower(1);
}
break;
case OPEN_GATE:
robot.setRapidFireBlockerPos(
ServoPositions.rapidFireBlocker_Open
);
if (stateTime() >= 100) {
setRapidMode(RapidMode.SHOOT);
}
robot.setTransferServoPos(ServoPositions.transferServo_in);
robot.setRapidFireBlockerPos(
ServoPositions.rapidFireBlocker_Open
);
if (Shooter.manualFlywheel) {
robot.setTransferPower(NewShooterTest.transferPower);
robot.setIntakePower(-NewShooterTest.transferPower);
} else {
robot.setTransferPower(commander.getTransferPow());
robot.setIntakePower(-commander.getTransferPow());
}
break;
case SHOOT:
robot.setTransferServoPos(
ServoPositions.transferServo_in
);
if (stateTime() >= 400) {
if (stateTime() >= 500) {
setRapidMode(RapidMode.INTAKE);
}
if (Shooter.manualFlywheel) {
robot.setTransferPower(NewShooterTest.transferPower);
robot.setIntakePower(-NewShooterTest.transferPower);
} else {
robot.setTransferPower(commander.getTransferPow());
robot.setIntakePower(-commander.getTransferPow());
}
holdBallsTicker = 0;
break;
}
break;
@@ -571,7 +583,7 @@ public class SpindexerTransferIntake {
break;
case WAIT_FOR_1:
if (shootStateTime() > 250) {
if (shootStateTime() > 400) {
setShootState(
SortedShootState.SHOOT_1
@@ -618,7 +630,7 @@ public class SpindexerTransferIntake {
break;
case WAIT_FOR_2:
if (shootStateTime() > 250) {
if (shootStateTime() > 400) {
setShootState(
SortedShootState.SHOOT_2
@@ -664,7 +676,7 @@ public class SpindexerTransferIntake {
break;
case WAIT_FOR_3:
if (shootStateTime() > 250) {
if (shootStateTime() > 400) {
setShootState(
SortedShootState.SHOOT_3

View File

@@ -20,12 +20,12 @@ public class Turret {
private final double turretMin = 0.05;
private final double turretMax = 0.95;
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;
PIDController bearingPID;
boolean bearingAligned = false;
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;
private double targetTx = 0;
private double currentTrackOffset = 0;

View File

@@ -8,87 +8,71 @@ public class VelocityCommander {
public static double xAccK = 0.025; // TODO: Tune
public static double yVelK = 0.05; // 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 transferPow = -1;
private double velo = 0;
private int velo = 0;
public VelocityCommander() {}
private final double veloA = -2.703087757*Math.pow(10, -14);
private final double veloB = 2.904756341*Math.pow(10, -11);
private final double veloC = -1.381814293*Math.pow(10, -8);
private final double veloD = 0.000003829224585;
private final double veloE = -0.000684090204;
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;
final double veloA = -0.00000133612;
final double veloB = 0.000542733;
final double veloC = -0.0739531;
final double veloD = 5.16759;
final double veloE = 62.45781;
private double distToRPM (double dist){
if (dist < 49) {
double currentVelo;
if (lockFront && dist > closeBound){
dist = closeBound;
} else if (lockBack && dist < farBound){
dist = farBound;
}
if (dist < 54) {
velo = 2000;
} else if (dist > 165){
velo = 3760;
} else if (dist > 181){
velo = 3600;
} else {
velo = veloA*Math.pow(dist, 10) +
veloB*Math.pow(dist, 9) +
veloC*Math.pow(dist, 8) +
veloD*Math.pow(dist, 7) +
veloE*Math.pow(dist, 6) +
veloF*Math.pow(dist, 5) +
veloG*Math.pow(dist, 4) +
veloH*Math.pow(dist, 3) +
veloI*Math.pow(dist, 2) +
veloJ*Math.pow(dist, 1) +
veloK;
velo = Math.max(2000, Math.min(3760, velo));
currentVelo = veloA*Math.pow(dist, 4) +
veloB*Math.pow(dist, 3) +
veloC*Math.pow(dist, 2) +
veloD*Math.pow(dist, 1) +
veloE;
velo = 10 * Math.round((float) Math.max(200, Math.min(360, currentVelo)));
}
return velo;
}
private final double hoodA = -4.3276177*Math.pow(10, -13);
private final double hoodB = 2.68062979*Math.pow(10, -10);
private final double hoodC = -7.12859632*Math.pow(10, -8);
private final double hoodD = 0.0000106010785;
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;
final double hoodA = 9.04203*Math.pow(10, -8);
final double hoodB = -0.0000204165;
final double hoodC = -0.00252089;
final double hoodD = 1.06154;
private void distToHood (double dist){
if (dist > 112){
hoodPos = 0.35;
} else if (dist < 49){
if (dist > 174){
hoodPos = 0.48;
} else if (dist < 54){
hoodPos = 0.88;
} else {
hoodPos = hoodA*Math.pow(dist, 8) +
hoodB*Math.pow(dist, 7) +
hoodC*Math.pow(dist, 6) +
hoodD*Math.pow(dist, 5) +
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 = hoodA*Math.pow(dist, 3) +
hoodB*Math.pow(dist, 2) +
hoodC*Math.pow(dist, 1) +
hoodD;
}
hoodPos = Math.max(0.48, Math.min(0.88, hoodPos));
}
public double getHoodPredicted(){
return hoodPos;
}
private void distToTransferPow(double dist, double voltage){
if (dist < 118){
transferPow = -1;
} else if (dist < 125){
transferPow = -0.7;
if (dist < 140){
transferPow = -0.8;
} else {
transferPow = -0.5;
}
// transferPow = Math.max(-0.5, Math.min(-1, transferPow * (14/voltage)));
}
public double getTransferPow(){return transferPow;}
@@ -98,7 +82,7 @@ public class VelocityCommander {
}
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 predictedDy = dy - (yVel * yVelK) - (0.5 * yAcc * yAccK); // Negative bc dy = target - robot
@@ -109,6 +93,17 @@ public class VelocityCommander {
distToHood(predictedDist);
distToTransferPow(predictedDist, voltage);
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;}