auto rewritten
This commit is contained in:
@@ -318,8 +318,13 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
obeliskTurrPos3 = turrDefault + blueObeliskTurrPos3;
|
||||
}
|
||||
|
||||
if (gateCycle) {
|
||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||
.strafeToLinearHeading(new Vector2d(x1, y1), Math.toRadians(h1));
|
||||
} else {
|
||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||
.strafeToLinearHeading(new Vector2d(xShoot0, yShoot0), Math.toRadians(hShoot0));
|
||||
}
|
||||
|
||||
if (gateCycle) {
|
||||
pickup1 = drive.actionBuilder(new Pose2d(xShootGate, yShootGate, Math.toRadians(hShootGate)))
|
||||
@@ -344,10 +349,17 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), Math.toRadians(hShoot));
|
||||
}
|
||||
|
||||
if (gateCycle) {
|
||||
pickup2 = drive.actionBuilder(new Pose2d(xShoot0, yShoot0, Math.toRadians(hShoot0)))
|
||||
.strafeToLinearHeading(new Vector2d(x3a, y3a), Math.toRadians(h3a))
|
||||
.strafeToLinearHeading(new Vector2d(x3b, y3b), Math.toRadians(h3b),
|
||||
new TranslationalVelConstraint(pickupStackGateSpeed));
|
||||
} else {
|
||||
pickup2 = drive.actionBuilder(new Pose2d(xShoot, yShoot, Math.toRadians(hShoot)))
|
||||
.strafeToLinearHeading(new Vector2d(x3a, y3a), Math.toRadians(h3a))
|
||||
.strafeToLinearHeading(new Vector2d(x3b, y3b), Math.toRadians(h3b),
|
||||
new TranslationalVelConstraint(pickup1Speed));
|
||||
}
|
||||
|
||||
if (gateCycle) {
|
||||
shoot2 = drive.actionBuilder(new Pose2d(x3b, y3b, Math.toRadians(h3b)))
|
||||
@@ -368,13 +380,6 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
shoot3 = drive.actionBuilder(new Pose2d(x4b, y4b, Math.toRadians(h4b)))
|
||||
.strafeToLinearHeading(new Vector2d(xLeave, yLeave), Math.toRadians(hLeave));
|
||||
|
||||
shoot0ToPickup2 = drive.actionBuilder(new Pose2d(0,0,0))
|
||||
.strafeToLinearHeading(new Vector2d(xShoot0, yShoot0), Math.toRadians(hShoot0))
|
||||
.waitSeconds(waitToPickupGate2)
|
||||
.strafeToLinearHeading(new Vector2d(x3a, y3a), Math.toRadians(h3a))
|
||||
.strafeToLinearHeading(new Vector2d(x3b, y3b), Math.toRadians(h3b),
|
||||
new TranslationalVelConstraint(pickupStackGateSpeed));
|
||||
|
||||
if (withPartner) {
|
||||
waitToPickupGate = waitToPickupGateWithPartner;
|
||||
} else {
|
||||
@@ -407,8 +412,10 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
if (gateCycle) {
|
||||
shoot0Gate();
|
||||
startAutoGate();
|
||||
shoot();
|
||||
cycleStackMiddleGate();
|
||||
shoot();
|
||||
|
||||
while (getRuntime() - stamp < endGateTime) {
|
||||
cycleGateIntake();
|
||||
@@ -460,12 +467,7 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
}
|
||||
|
||||
void shoot() {
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease)
|
||||
)
|
||||
|
||||
);
|
||||
Actions.runBlocking(autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease));
|
||||
}
|
||||
|
||||
void startAuto() {
|
||||
@@ -485,6 +487,23 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
);
|
||||
}
|
||||
|
||||
void startAutoGate() {
|
||||
assert shoot0 != null;
|
||||
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot0.build(),
|
||||
autoActions.manageShooterAuto(
|
||||
flywheel0Time,
|
||||
xShoot0,
|
||||
yShoot0,
|
||||
hShoot0,
|
||||
false
|
||||
)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
void cycleStackClose() {
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
@@ -636,59 +655,30 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
);
|
||||
}
|
||||
|
||||
void shoot0Gate(){
|
||||
void cycleStackMiddleGate() {
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot0ToPickup2.build(),
|
||||
new SequentialAction(
|
||||
new ParallelAction(
|
||||
autoActions.manageShooterManual(
|
||||
waitToShoot0,
|
||||
0.501,
|
||||
velGate0Start,
|
||||
hoodGate0Start,
|
||||
velGate0Start,
|
||||
hoodGate0Start,
|
||||
0.501
|
||||
)
|
||||
),
|
||||
autoActions.shootAllManual(
|
||||
shootAllTime,
|
||||
hood0MoveTime,
|
||||
spindexerSpeedIncrease,
|
||||
velGate0Start,
|
||||
hoodGate0Start,
|
||||
velGate0End,
|
||||
hoodGate0End,
|
||||
0.501),
|
||||
pickup2.build(),
|
||||
autoActions.intake(
|
||||
intake2TimeGate,
|
||||
xShootGate,
|
||||
yShootGate,
|
||||
hShootGate
|
||||
)
|
||||
intake2Time,
|
||||
x3b,
|
||||
y3b,
|
||||
h3b
|
||||
)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
void cycleStackMiddleGate(){
|
||||
servos.setSpinPos(spinStartPos);
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot2.build(),
|
||||
new SequentialAction(
|
||||
new ParallelAction(
|
||||
autoActions.manageShooterAuto(
|
||||
shoot2GateTime,
|
||||
autoActions.prepareShootAll(
|
||||
colorSenseTime,
|
||||
shoot2Time,
|
||||
motif,
|
||||
xShootGate,
|
||||
yShootGate,
|
||||
hShootGate,
|
||||
false
|
||||
)
|
||||
),
|
||||
autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease)
|
||||
)
|
||||
hShootGate)
|
||||
)
|
||||
);
|
||||
}
|
||||
@@ -712,8 +702,6 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
gateCycleShoot.build(),
|
||||
new SequentialAction(
|
||||
new ParallelAction(
|
||||
autoActions.manageShooterAuto(
|
||||
shootGateTime,
|
||||
xShootGate,
|
||||
@@ -721,9 +709,6 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
hShootGate,
|
||||
false
|
||||
)
|
||||
),
|
||||
autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease)
|
||||
)
|
||||
)
|
||||
);
|
||||
}
|
||||
@@ -747,8 +732,6 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot1.build(),
|
||||
new SequentialAction(
|
||||
new ParallelAction(
|
||||
autoActions.manageShooterAuto(
|
||||
shoot1GateTime,
|
||||
xLeaveGate,
|
||||
@@ -756,9 +739,6 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
hLeaveGate,
|
||||
false
|
||||
)
|
||||
),
|
||||
autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease)
|
||||
)
|
||||
)
|
||||
);
|
||||
}
|
||||
|
||||
@@ -131,7 +131,6 @@ public class Turret {
|
||||
}
|
||||
if (xPos != null){
|
||||
if (zPos>0) {
|
||||
|
||||
limelightTagX = (alphaPosConstant * xPos) + ((1 - alphaPosConstant) * limelightTagX);
|
||||
limelightTagY = (alphaPosConstant * yPos) + ((1 - alphaPosConstant) * limelightTagY);
|
||||
limelightTagZ = (alphaPosConstant * zPos) + ((1 - alphaPosConstant) * limelightTagZ);
|
||||
|
||||
Reference in New Issue
Block a user