Compare commits
11 Commits
194100e3c8
...
master
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
7043274ebd | ||
|
|
bd05090afe | ||
|
|
369e379eb4 | ||
|
|
41853e9ad1 | ||
| c01edd9308 | |||
| ccfac3e123 | |||
| 395d4439db | |||
| 5f33cb4d41 | |||
| e92f11bc69 | |||
| 457eaf5feb | |||
| dc9886855b |
@@ -5,10 +5,16 @@ import static org.firstinspires.ftc.teamcode.constants.Front_Poses.*;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos2;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos3;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.redObeliskTurrPos0;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.redObeliskTurrPos1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.redObeliskTurrPos2;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.redObeliskTurrPos3;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3b;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Turret.turrDefault;
|
||||
@@ -53,14 +59,14 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
public static double hood0MoveTime = 2;
|
||||
public static double spindexerSpeedIncrease = 0.014;
|
||||
|
||||
public static double shootAllTime = 3.5;
|
||||
public static double shootAllTime = 6.0;
|
||||
public static double intake1Time = 3.3;
|
||||
public static double intake2Time = 3.8;
|
||||
public static double intake2Time = 4.2;
|
||||
|
||||
public static double intake3Time = 4.2;
|
||||
public static double intake3Time = 5.4;
|
||||
|
||||
public static double flywheel0Time = 1.5;
|
||||
public static double pickup1Speed = 12;
|
||||
public static double flywheel0Time = 1.9;
|
||||
public static double pickup1Speed = 14;
|
||||
// ---- POSITION TOLERANCES ----
|
||||
public static double posXTolerance = 5.0;
|
||||
public static double posYTolerance = 5.0;
|
||||
@@ -127,6 +133,7 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
double obeliskTurrPos2 = 0.0;
|
||||
double obeliskTurrPos3 = 0.0;
|
||||
double waitToPickupGate = 0;
|
||||
double obeliskTurrPosAutoStart = 0;
|
||||
|
||||
// initialize path variables here
|
||||
TrajectoryActionBuilder shoot0 = null;
|
||||
@@ -168,19 +175,45 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
|
||||
autoActions = new AutoActions(robot, drive, TELE, servos, flywheel, spindexer, targeting, targetingSettings, turret, light);
|
||||
|
||||
servos.setSpinPos(spinStartPos);
|
||||
servos.setSpinPos(spindexer_intakePos1);
|
||||
|
||||
servos.setTransferPos(transferServo_out);
|
||||
|
||||
limelightUsed = true;
|
||||
limelightUsed = false;
|
||||
|
||||
robot.light.setPosition(1);
|
||||
|
||||
hardwareMap.get(GoBildaPinpointDriver.class, "pinpoint").resetPosAndIMU();
|
||||
|
||||
|
||||
while (opModeInInit()) {
|
||||
if (limelightUsed && !gateCycle){
|
||||
Actions.runBlocking(
|
||||
autoActions.detectObelisk(
|
||||
0.1,
|
||||
0.501,
|
||||
0.501,
|
||||
0.501,
|
||||
0.501,
|
||||
obeliskTurrPosAutoStart
|
||||
)
|
||||
);
|
||||
motif = turret.getObeliskID();
|
||||
|
||||
if (motif == 21){
|
||||
AutoActions.firstSpindexShootPos = spindexer_outtakeBall1;
|
||||
} else if (motif == 22){
|
||||
AutoActions.firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||
} else {
|
||||
AutoActions.firstSpindexShootPos = spindexer_outtakeBall2;
|
||||
}
|
||||
}
|
||||
|
||||
if (!gateCycle) {
|
||||
turret.pipelineSwitch(1);
|
||||
} else if (redAlliance) {
|
||||
turret.pipelineSwitch(4);
|
||||
} else {
|
||||
turret.pipelineSwitch(2);
|
||||
}
|
||||
|
||||
if (gateCycle) {
|
||||
servos.setHoodPos(hoodGate0Start);
|
||||
@@ -188,8 +221,6 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
servos.setHoodPos(shoot0Hood);
|
||||
}
|
||||
|
||||
turret.setTurret(turrDefault);
|
||||
|
||||
if (gamepad2.crossWasPressed()) {
|
||||
redAlliance = !redAlliance;
|
||||
}
|
||||
@@ -209,24 +240,17 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
ballCycles--;
|
||||
}
|
||||
|
||||
if (gamepad2.triangleWasPressed()){
|
||||
gateCycle = !gateCycle;
|
||||
}
|
||||
|
||||
|
||||
|
||||
if (gamepad2.squareWasPressed()) {
|
||||
|
||||
|
||||
drive = new MecanumDrive(hardwareMap,new Pose2d(0,0,0));
|
||||
|
||||
|
||||
if (!gateCycle) {
|
||||
turret.pipelineSwitch(1);
|
||||
} else if (redAlliance) {
|
||||
turret.pipelineSwitch(4);
|
||||
} else {
|
||||
turret.pipelineSwitch(2);
|
||||
}
|
||||
robot.limelight.start();
|
||||
|
||||
|
||||
limelightUsed = true;
|
||||
|
||||
gamepad2.rumble(500);
|
||||
}
|
||||
@@ -283,6 +307,7 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
pickupGateBY = rPickupGateBY;
|
||||
pickupGateBH = rPickupGateBH;
|
||||
|
||||
obeliskTurrPosAutoStart = turrDefault + redObeliskTurrPos0;
|
||||
obeliskTurrPos1 = turrDefault + redObeliskTurrPos1;
|
||||
obeliskTurrPos2 = turrDefault + redObeliskTurrPos2;
|
||||
obeliskTurrPos3 = turrDefault + redObeliskTurrPos3;
|
||||
@@ -338,6 +363,7 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
pickupGateBY = bPickupGateBY;
|
||||
pickupGateBH = bPickupGateBH;
|
||||
|
||||
obeliskTurrPosAutoStart = turrDefault + redObeliskTurrPos0;
|
||||
obeliskTurrPos1 = turrDefault + blueObeliskTurrPos1;
|
||||
obeliskTurrPos2 = turrDefault + blueObeliskTurrPos2;
|
||||
obeliskTurrPos3 = turrDefault + blueObeliskTurrPos3;
|
||||
@@ -414,10 +440,6 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), Math.toRadians(hShoot));
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
pickup3 = drive.actionBuilder(new Pose2d(xShoot, yShoot, Math.toRadians(hShoot)))
|
||||
.strafeToLinearHeading(new Vector2d(x4a, y4a), Math.toRadians(h4a))
|
||||
.strafeToLinearHeading(new Vector2d(x4b, y4b), Math.toRadians(h4b),
|
||||
@@ -432,13 +454,13 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
waitToPickupGate = waitToPickupGateSolo;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
teleStart = drive.localizer.getPose();
|
||||
TELE.addData("Red?", redAlliance);
|
||||
TELE.addData("Turret Default", turrDefault);
|
||||
TELE.addData("Gate Cycle?", gateCycle);
|
||||
TELE.addData("Ball Cycles", ballCycles);
|
||||
TELE.addData("Limelight Started?", limelightUsed);
|
||||
TELE.addData("Motif", motif);
|
||||
|
||||
TELE.update();
|
||||
}
|
||||
@@ -456,15 +478,15 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
|
||||
if (gateCycle) {
|
||||
startAutoGate();
|
||||
shoot();
|
||||
shoot(0.501, 0.501, 0.501);
|
||||
cycleStackMiddleGate();
|
||||
shoot();
|
||||
shoot(0.501,0.501, 0.501);
|
||||
|
||||
while (getRuntime() - stamp < endGateTime) {
|
||||
cycleGateIntake();
|
||||
if (getRuntime() - stamp < lastShootTime) {
|
||||
cycleGateShoot();
|
||||
shoot();
|
||||
shoot(0.501, 0.501, 0.501);
|
||||
}
|
||||
}
|
||||
cycleStackCloseIntakeGate();
|
||||
@@ -473,25 +495,28 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
cycleStackCloseShootGate();
|
||||
}
|
||||
|
||||
shoot();
|
||||
shoot(0.501, 0.501, 0.501);
|
||||
|
||||
} else {
|
||||
|
||||
|
||||
|
||||
startAuto();
|
||||
shoot();
|
||||
shoot(0.501, 0.501,0.501);
|
||||
|
||||
if (ballCycles > 0) {
|
||||
cycleStackClose();
|
||||
shoot();
|
||||
shoot(xShoot, yShoot, hShoot);
|
||||
}
|
||||
|
||||
if (ballCycles > 1) {
|
||||
cycleStackMiddle();
|
||||
shoot();
|
||||
shoot(xShoot, yShoot, hShoot);
|
||||
}
|
||||
|
||||
if (ballCycles > 2) {
|
||||
cycleStackFar();
|
||||
shoot();
|
||||
shoot(xLeave, yLeave, hLeave);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -512,8 +537,8 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
|
||||
}
|
||||
|
||||
void shoot() {
|
||||
Actions.runBlocking(autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease));
|
||||
void shoot(double x, double y, double z) {
|
||||
Actions.runBlocking(autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease, x, y, z));
|
||||
}
|
||||
|
||||
void startAuto() {
|
||||
@@ -522,15 +547,17 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot0.build(),
|
||||
autoActions.manageShooterAuto(
|
||||
autoActions.prepareShootAll(
|
||||
0.8,
|
||||
flywheel0Time,
|
||||
motif,
|
||||
x1,
|
||||
y1,
|
||||
h1,
|
||||
false
|
||||
h1
|
||||
)
|
||||
)
|
||||
);
|
||||
|
||||
}
|
||||
|
||||
|
||||
@@ -541,15 +568,18 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
shoot0.build(),
|
||||
autoActions.manageShooterAuto(
|
||||
autoActions.prepareShootAll(
|
||||
colorSenseTime,
|
||||
flywheel0Time,
|
||||
motif,
|
||||
xShoot0,
|
||||
yShoot0,
|
||||
hShoot0,
|
||||
false
|
||||
hShoot0
|
||||
)
|
||||
)
|
||||
);
|
||||
|
||||
|
||||
}
|
||||
|
||||
void cycleStackClose() {
|
||||
@@ -561,24 +591,10 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
x2b,
|
||||
y2b,
|
||||
h2b
|
||||
),
|
||||
autoActions.detectObelisk(
|
||||
intake1Time,
|
||||
x2b,
|
||||
y2b,
|
||||
posXTolerance,
|
||||
posYTolerance,
|
||||
obeliskTurrPos1
|
||||
)
|
||||
|
||||
)
|
||||
);
|
||||
|
||||
motif = turret.getObeliskID();
|
||||
|
||||
if (motif == 0) motif = 22;
|
||||
prevMotif = motif;
|
||||
|
||||
double posX;
|
||||
double posY;
|
||||
double posH;
|
||||
@@ -616,24 +632,10 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
x3b,
|
||||
y3b,
|
||||
h3b
|
||||
),
|
||||
autoActions.detectObelisk(
|
||||
intake2Time,
|
||||
x3b,
|
||||
y3b,
|
||||
posXTolerance,
|
||||
posYTolerance,
|
||||
obeliskTurrPos2
|
||||
)
|
||||
|
||||
)
|
||||
);
|
||||
|
||||
motif = turret.getObeliskID();
|
||||
|
||||
if (motif == 0) motif = prevMotif;
|
||||
prevMotif = motif;
|
||||
|
||||
double posX;
|
||||
double posY;
|
||||
double posH;
|
||||
@@ -670,16 +672,7 @@ public class Auto_LT_Close extends LinearOpMode {
|
||||
x4b,
|
||||
y4b,
|
||||
h4b
|
||||
),
|
||||
autoActions.detectObelisk(
|
||||
intake3Time,
|
||||
x4b,
|
||||
y4b,
|
||||
posXTolerance,
|
||||
posYTolerance,
|
||||
obeliskTurrPos3
|
||||
)
|
||||
|
||||
)
|
||||
);
|
||||
|
||||
|
||||
@@ -321,7 +321,7 @@ public class Auto_LT_Far extends LinearOpMode {
|
||||
void shoot(){
|
||||
Actions.runBlocking(
|
||||
new ParallelAction(
|
||||
autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease)
|
||||
autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease, 0.501, 0.501, 0.501)
|
||||
)
|
||||
|
||||
);
|
||||
|
||||
@@ -18,7 +18,10 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||
import com.acmerobotics.roadrunner.Action;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.constants.Color;
|
||||
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
|
||||
import org.firstinspires.ftc.teamcode.constants.StateEnums;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
@@ -48,7 +51,7 @@ public class AutoActions {
|
||||
private int passengerSlotGreen = 0;
|
||||
private int rearSlotGreen = 0;
|
||||
private int mostGreenSlot = 0;
|
||||
private double firstSpindexShootPos = spinStartPos;
|
||||
public static double firstSpindexShootPos = spinStartPos;
|
||||
private boolean shootForward = true;
|
||||
public int motif = 0;
|
||||
double spinEndPos = ServoPositions.spinEndPos;
|
||||
@@ -85,13 +88,13 @@ public class AutoActions {
|
||||
void spin1PosFirst() {
|
||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||
shootForward = true;
|
||||
spinEndPos = spindexer_outtakeBall3 + 0.1;
|
||||
spinEndPos = 0.95;
|
||||
}
|
||||
|
||||
void spin2PosFirst() {
|
||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
||||
shootForward = false;
|
||||
spinEndPos = spindexer_outtakeBall3b - 0.1;
|
||||
spinEndPos = 0.05;
|
||||
}
|
||||
|
||||
void reverseSpin2PosFirst() {
|
||||
@@ -103,13 +106,13 @@ public class AutoActions {
|
||||
void spin3PosFirst() {
|
||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
||||
shootForward = false;
|
||||
spinEndPos = spindexer_outtakeBall1 - 0.1;
|
||||
spinEndPos = 0.05;
|
||||
}
|
||||
|
||||
void oddSpin3PosFirst() {
|
||||
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||
shootForward = true;
|
||||
spinEndPos = spindexer_outtakeBall2 + 0.1;
|
||||
spinEndPos = 0.95;
|
||||
}
|
||||
|
||||
Action manageShooter = null;
|
||||
@@ -119,6 +122,9 @@ public class AutoActions {
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
manageShooter = manageShooterAuto(time, posX, posY, posH, false);
|
||||
driverSlotGreen = 0;
|
||||
passengerSlotGreen = 0;
|
||||
rearSlotGreen = 0;
|
||||
}
|
||||
ticker++;
|
||||
servos.setTransferPos(transferServo_out);
|
||||
@@ -130,27 +136,50 @@ public class AutoActions {
|
||||
|
||||
manageShooter.run(telemetryPacket);
|
||||
|
||||
TELE.addData("Most Green Slot", mostGreenSlot);
|
||||
TELE.addData("Driver Slot Greeness", driverSlotGreen);
|
||||
TELE.addData("Passenger Slot Greeness", passengerSlotGreen);
|
||||
TELE.addData("Rear Greeness", rearSlotGreen);
|
||||
TELE.update();
|
||||
|
||||
if ((System.currentTimeMillis() - stamp) < (colorSenseTime * 1000)) {
|
||||
|
||||
spindexerWiggle *= -1.0;
|
||||
|
||||
servos.setSpinPos(spindexer_intakePos1 + spindexerWiggle);
|
||||
|
||||
spindexer.detectBalls(true, true);
|
||||
|
||||
if (Objects.equals(spindexer.GetFrontDriverColor(), Spindexer.BallColor.GREEN)) {
|
||||
driverSlotGreen++;
|
||||
// Rear Center (Position 1)
|
||||
double distanceRearCenter = robot.color1.getDistance(DistanceUnit.MM);
|
||||
if (distanceRearCenter < 52) {
|
||||
NormalizedRGBA color1RGBA = robot.color1.getNormalizedColors();
|
||||
double gP1 = color1RGBA.green / (color1RGBA.green + color1RGBA.red + color1RGBA.blue);
|
||||
if (gP1 >= 0.38) {
|
||||
rearSlotGreen++;
|
||||
}
|
||||
}
|
||||
|
||||
if (Objects.equals(spindexer.GetFrontPassengerColor(), Spindexer.BallColor.GREEN)) {
|
||||
passengerSlotGreen++;
|
||||
// Front Driver (Position 2)
|
||||
double distanceFrontDriver = robot.color2.getDistance(DistanceUnit.MM);
|
||||
if (distanceFrontDriver < 50) {
|
||||
NormalizedRGBA color2RGBA = robot.color2.getNormalizedColors();
|
||||
double gP2 = color2RGBA.green / (color2RGBA.green + color2RGBA.red + color2RGBA.blue);
|
||||
if (gP2 >= 0.4) {
|
||||
driverSlotGreen++;
|
||||
}
|
||||
}
|
||||
|
||||
if (Objects.equals(spindexer.GetRearCenterColor(), Spindexer.BallColor.GREEN)) {
|
||||
rearSlotGreen++;
|
||||
// Front Passenger (Position 3)
|
||||
double distanceFrontPassenger = robot.color3.getDistance(DistanceUnit.MM);
|
||||
if (distanceFrontPassenger < 29) {
|
||||
NormalizedRGBA color3RGBA = robot.color3.getNormalizedColors();
|
||||
double gP3 = color3RGBA.green / (color3RGBA.green + color3RGBA.red + color3RGBA.blue);
|
||||
if (gP3 >= 0.4) {
|
||||
passengerSlotGreen++;
|
||||
}
|
||||
}
|
||||
|
||||
spindexer.setIntakePower(1);
|
||||
spindexer.setIntakePower(-0.1);
|
||||
|
||||
decideGreenSlot = true;
|
||||
|
||||
@@ -169,29 +198,46 @@ public class AutoActions {
|
||||
|
||||
if (motif_id == 21) {
|
||||
if (mostGreenSlot == 1) {
|
||||
spin1PosFirst();
|
||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95;
|
||||
} else if (mostGreenSlot == 2) {
|
||||
spin2PosFirst();
|
||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
||||
shootForward = false;
|
||||
spinEndPos = 0.05;
|
||||
} else {
|
||||
spin3PosFirst();
|
||||
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95;
|
||||
}
|
||||
} else if (motif_id == 22) {
|
||||
if (mostGreenSlot == 1) {
|
||||
spin2PosFirst();
|
||||
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95;
|
||||
} else if (mostGreenSlot == 2) {
|
||||
spin3PosFirst();
|
||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95;
|
||||
} else {
|
||||
reverseSpin2PosFirst();
|
||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||
shootForward = false;
|
||||
spinEndPos = 0.03;
|
||||
}
|
||||
|
||||
} else {
|
||||
if (mostGreenSlot == 1) {
|
||||
spin3PosFirst();
|
||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
||||
shootForward = false;
|
||||
spinEndPos = 0.05;
|
||||
} else if (mostGreenSlot == 2) {
|
||||
oddSpin3PosFirst();
|
||||
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95;
|
||||
} else {
|
||||
spin1PosFirst();
|
||||
}
|
||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||
shootForward = true;
|
||||
spinEndPos = 0.95; }
|
||||
}
|
||||
|
||||
return true;
|
||||
@@ -209,7 +255,7 @@ public class AutoActions {
|
||||
};
|
||||
}
|
||||
|
||||
public Action shootAllAuto(double shootTime, double spindexSpeed) {
|
||||
public Action shootAllAuto(double shootTime, double spindexSpeed, double posX, double posY, double posH) {
|
||||
return new Action() {
|
||||
int ticker = 1;
|
||||
|
||||
@@ -231,7 +277,7 @@ public class AutoActions {
|
||||
|
||||
if (ticker == 1) {
|
||||
stamp = System.currentTimeMillis();
|
||||
manageShooter = manageShooterAuto(shootTime, 0.501, 0.501, 0.501, false);
|
||||
manageShooter = manageShooterAuto(shootTime, posX, posY, posH, false);
|
||||
|
||||
}
|
||||
ticker++;
|
||||
@@ -242,9 +288,9 @@ public class AutoActions {
|
||||
|
||||
boolean end;
|
||||
if (shootForward) {
|
||||
end = prevSpinPos > spinEndPos;
|
||||
end = servos.getSpinPos() > spinEndPos;
|
||||
} else {
|
||||
end = prevSpinPos < spinEndPos;
|
||||
end = servos.getSpinPos() < spinEndPos;
|
||||
}
|
||||
|
||||
if (System.currentTimeMillis() - stamp < shootTime * 1000 && (!end || shooterTicker < Spindexer.waitFirstBallTicks + 1)) {
|
||||
@@ -379,8 +425,8 @@ public class AutoActions {
|
||||
|
||||
manageShooter.run(telemetryPacket);
|
||||
|
||||
if ((System.currentTimeMillis() - stamp) > (time * 1000) || spindexer.isFull()) {
|
||||
spindexer.setIntakePower(-0.1);
|
||||
if ((System.currentTimeMillis() - stamp) > (time * 1000)) {
|
||||
servos.setSpinPos(spindexer_intakePos1);
|
||||
return false;
|
||||
} else {
|
||||
return true;
|
||||
@@ -408,6 +454,7 @@ public class AutoActions {
|
||||
|
||||
double stamp = 0.0;
|
||||
int ticker = 0;
|
||||
int prevMotif = 0;
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
@@ -418,18 +465,23 @@ public class AutoActions {
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
turret.pipelineSwitch(1);
|
||||
ticker++;
|
||||
}
|
||||
|
||||
ticker++;
|
||||
motif = turret.detectObelisk();
|
||||
|
||||
if (prevMotif == motif){
|
||||
ticker++;
|
||||
}
|
||||
prevMotif = motif;
|
||||
|
||||
turret.setTurret(turrPos);
|
||||
|
||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
||||
|
||||
boolean shouldFinish = timeDone || (xDone && yDone) || spindexer.isFull();
|
||||
boolean shouldFinish = timeDone || (xDone && yDone) || spindexer.isFull() || ticker > 10;
|
||||
|
||||
teleStart = currentPose;
|
||||
|
||||
@@ -464,14 +516,26 @@ public class AutoActions {
|
||||
|
||||
final boolean timeFallback = (time != 0.501);
|
||||
|
||||
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
|
||||
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
Pose2d currentPose = drive.localizer.getPose();
|
||||
|
||||
if (ticker == 0) {
|
||||
stamp = System.currentTimeMillis();
|
||||
|
||||
if (redAlliance) {
|
||||
turret.pipelineSwitch(4);
|
||||
light.setManualLightColor(Color.LightRed);
|
||||
} else {
|
||||
turret.pipelineSwitch(2);
|
||||
light.setManualLightColor(Color.LightBlue);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
ticker++;
|
||||
@@ -486,14 +550,15 @@ public class AutoActions {
|
||||
|
||||
double dx = robotX - goalX; // delta x from robot to goal
|
||||
double dy = robotY - goalY; // delta y from robot to goal
|
||||
|
||||
|
||||
Pose2d deltaPose;
|
||||
if (posX != 0.501) {
|
||||
deltaPose = new Pose2d(posX, posY, Math.toRadians(posH));
|
||||
Turret.limelightUsed = false;
|
||||
} else {
|
||||
deltaPose = new Pose2d(dx, dy, robotHeading);
|
||||
Turret.limelightUsed = true;
|
||||
}
|
||||
Turret.limelightUsed = true;
|
||||
|
||||
// double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||
|
||||
|
||||
@@ -10,10 +10,10 @@ public class Front_Poses {
|
||||
public static double rx1 = 20, ry1 = 0.5, rh1 = 0.1;
|
||||
public static double bx1 = 20, by1 = -0.5, bh1 = -0.1;
|
||||
|
||||
public static double rx2a = 41, ry2a = 18, rh2a = 155;
|
||||
public static double rx2a = 41, ry2a = 18, rh2a = 140;
|
||||
public static double bx2a = 41, by2a = -18, bh2a = -140;
|
||||
|
||||
public static double rx2b = 21, ry2b = 34, rh2b = 155.1;
|
||||
public static double rx2b = 21, ry2b = 34, rh2b = 140.1;
|
||||
public static double bx2b = 23, by2b = -36, bh2b = -140.1;
|
||||
|
||||
public static double rx3a = 55, ry3a = 39, rh3a = 140;
|
||||
|
||||
@@ -5,18 +5,18 @@ import com.acmerobotics.dashboard.config.Config;
|
||||
@Config
|
||||
public class ServoPositions {
|
||||
|
||||
public static double spindexer_intakePos1 = 0.22; //0.13;
|
||||
public static double spindexer_intakePos1 = 0.18; //0.13;
|
||||
|
||||
public static double spindexer_intakePos2 = 0.41; //0.33;//0.5;
|
||||
public static double spindexer_intakePos2 = 0.37; //0.33;//0.5;
|
||||
|
||||
public static double spindexer_intakePos3 = 0.60; //0.53;//0.66;
|
||||
public static double spindexer_intakePos3 = 0.56; //0.53;//0.66;
|
||||
|
||||
public static double spindexer_outtakeBall3 = 0.88; //0.65; //0.24;
|
||||
public static double spindexer_outtakeBall3b = 0.31; //0.65; //0.24;
|
||||
public static double spindexer_outtakeBall3 = 0.84; //0.65; //0.24;
|
||||
public static double spindexer_outtakeBall3b = 0.27; //0.65; //0.24;
|
||||
|
||||
public static double spindexer_outtakeBall2 = 0.7; //0.46; //0.6;
|
||||
public static double spindexer_outtakeBall1 = 0.51; //0.27; //0.4;
|
||||
public static double spinStartPos = 0.14;
|
||||
public static double spindexer_outtakeBall2 = 0.66; //0.46; //0.6;
|
||||
public static double spindexer_outtakeBall1 = 0.47; //0.27; //0.4;
|
||||
public static double spinStartPos = 0.10;
|
||||
public static double spinEndPos = 0.95;
|
||||
|
||||
public static double shootAllSpindexerSpeedIncrease = 0.014;
|
||||
@@ -33,12 +33,14 @@ public class ServoPositions {
|
||||
public static double turret_blueClose = 0;
|
||||
|
||||
// These values are ADDED to turrDefault
|
||||
public static double redObeliskTurrPos1 = 0.12;
|
||||
public static double redObeliskTurrPos2 = 0.13;
|
||||
public static double redObeliskTurrPos3 = 0.14;
|
||||
public static double blueObeliskTurrPos1 = -0.12;
|
||||
public static double blueObeliskTurrPos2 = -0.13;
|
||||
public static double blueObeliskTurrPos3 = -0.14;
|
||||
public static double redObeliskTurrPos0 = -0.35;
|
||||
public static double redObeliskTurrPos1 = 0.15;
|
||||
public static double redObeliskTurrPos2 = 0.16;
|
||||
public static double redObeliskTurrPos3 = 0.17;
|
||||
public static double blueObeliskTurrPos0 = 0.35;
|
||||
public static double blueObeliskTurrPos1 = -0.15;
|
||||
public static double blueObeliskTurrPos2 = -0.16;
|
||||
public static double blueObeliskTurrPos3 = -0.17;
|
||||
public static double redTurretShootPos = 0.05;
|
||||
public static double blueTurretShootPos = -0.05;
|
||||
|
||||
|
||||
@@ -45,9 +45,9 @@ public class TeleopV3 extends LinearOpMode {
|
||||
public double vel = 3000;
|
||||
public boolean autoVel = true;
|
||||
public boolean targetingHood = true;
|
||||
// public boolean autoHood = true;
|
||||
// public boolean autoHood = true;
|
||||
public double shootStamp = 0.0;
|
||||
// boolean fixedTurret = false;
|
||||
// boolean fixedTurret = false;
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
Light light;
|
||||
@@ -66,10 +66,10 @@ public class TeleopV3 extends LinearOpMode {
|
||||
double xOffset = 0.0;
|
||||
double yOffset = 0.0;
|
||||
double hOffset = 0.0;
|
||||
// double headingOffset = 0.0;
|
||||
// double headingOffset = 0.0;
|
||||
int ticker = 0;
|
||||
|
||||
// boolean autoSpintake = false;
|
||||
// boolean autoSpintake = false;
|
||||
boolean enableSpindexerManager = true;
|
||||
|
||||
// boolean overrideTurr = false;
|
||||
@@ -142,12 +142,7 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
//DRIVETRAIN:
|
||||
|
||||
drivetrain.drive(
|
||||
-gamepad1.right_stick_y,
|
||||
gamepad1.right_stick_x,
|
||||
gamepad1.left_stick_x,
|
||||
gamepad1.left_trigger
|
||||
);
|
||||
drivetrain.drive(-gamepad1.right_stick_y, gamepad1.right_stick_x, gamepad1.left_stick_x, gamepad1.left_trigger);
|
||||
|
||||
if (gamepad1.right_bumper) {
|
||||
|
||||
@@ -156,10 +151,10 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
light.setState(StateEnums.LightState.BALL_COUNT);
|
||||
|
||||
} else if (gamepad2.triangle){
|
||||
} else if (gamepad2.triangle) {
|
||||
light.setState(StateEnums.LightState.BALL_COLOR);
|
||||
|
||||
} else {
|
||||
} else {
|
||||
light.setState(StateEnums.LightState.GOAL_LOCK);
|
||||
}
|
||||
|
||||
@@ -182,17 +177,16 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
// double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||
|
||||
targetingSettings = targeting.calculateSettings
|
||||
(robotX, robotY, robotHeading, 0.0, turretInterpolate);
|
||||
targetingSettings = targeting.calculateSettings(robotX, robotY, robotHeading, 0.0, turretInterpolate);
|
||||
|
||||
//RELOCALIZATION
|
||||
|
||||
if (gamepad2.squareWasPressed()){
|
||||
if (gamepad2.squareWasPressed()) {
|
||||
relocalize = !relocalize;
|
||||
gamepad2.rumble(500);
|
||||
}
|
||||
|
||||
if (relocalize){
|
||||
if (relocalize) {
|
||||
turret.relocalize();
|
||||
xOffset = -((turret.getLimelightZ() * 39.3701) + Turret.limelightPosOffset) - robX;
|
||||
yOffset = (turret.getLimelightX() * 39.3701) - robY;
|
||||
@@ -231,6 +225,7 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
//HOOD:
|
||||
|
||||
|
||||
if (targetingHood) {
|
||||
servo.setHoodPos(targetingSettings.hoodAngle + autoHoodOffset);
|
||||
} else {
|
||||
@@ -267,7 +262,6 @@ public class TeleopV3 extends LinearOpMode {
|
||||
}
|
||||
|
||||
|
||||
|
||||
if (enableSpindexerManager) {
|
||||
//if (!shootAll) {
|
||||
spindexer.processIntake();
|
||||
@@ -299,7 +293,7 @@ public class TeleopV3 extends LinearOpMode {
|
||||
if (shooterTicker == 0) {
|
||||
spindexer.prepareShootAllContinous();
|
||||
//TELE.addLine("preparing to shoot");
|
||||
// } else if (shooterTicker == 2) {
|
||||
// else if (shooterTicker == 2) {
|
||||
// //servo.setTransferPos(transferServo_in);
|
||||
// spindexer.shootAll();
|
||||
// TELE.addLine("starting to shoot");
|
||||
|
||||
@@ -7,6 +7,7 @@ import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
@@ -28,16 +29,20 @@ public class ColorTest extends LinearOpMode {
|
||||
if (isStopRequested()) return;
|
||||
|
||||
while(opModeIsActive()){
|
||||
double green1 = robot.color1.getNormalizedColors().green;
|
||||
double blue1 = robot.color1.getNormalizedColors().blue;
|
||||
double red1 = robot.color1.getNormalizedColors().red;
|
||||
|
||||
|
||||
NormalizedRGBA color1RGBA = robot.color1.getNormalizedColors();
|
||||
|
||||
double gP1 = color1RGBA.green / (color1RGBA.green + color1RGBA.red + color1RGBA.blue);
|
||||
|
||||
double dist1 = robot.color1.getDistance(DistanceUnit.MM);
|
||||
color1Distance = (colorFilterAlpha * dist1) + ((1-colorFilterAlpha) * color1Distance);
|
||||
|
||||
TELE.addData("Color1 toColor", robot.color1.getNormalizedColors().toColor());
|
||||
TELE.addData("Color1 green", green1 / (green1 + blue1 + red1));
|
||||
TELE.addData("Color1 green", gP1);
|
||||
TELE.addData("Color1 distance (mm)", color1Distance);
|
||||
|
||||
|
||||
// ----- COLOR 2 -----
|
||||
double green2 = robot.color2.getNormalizedColors().green;
|
||||
double blue2 = robot.color2.getNormalizedColors().blue;
|
||||
|
||||
@@ -0,0 +1,110 @@
|
||||
package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.autonomous.actions.AutoActions;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.Light;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
||||
import org.firstinspires.ftc.teamcode.utils.Spindexer;
|
||||
import org.firstinspires.ftc.teamcode.utils.Targeting;
|
||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
||||
|
||||
@Config
|
||||
@TeleOp
|
||||
public class SortingTest extends LinearOpMode {
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
MecanumDrive drive;
|
||||
Servos servos;
|
||||
Spindexer spindexer;
|
||||
Flywheel flywheel;
|
||||
Turret turret;
|
||||
Targeting targeting;
|
||||
Targeting.Settings targetingSettings;
|
||||
AutoActions autoActions;
|
||||
Light light;
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
robot = new Robot(hardwareMap);
|
||||
|
||||
TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
);
|
||||
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
|
||||
targeting = new Targeting();
|
||||
targetingSettings = new Targeting.Settings(0.0, 0.0);
|
||||
|
||||
spindexer = new Spindexer(hardwareMap);
|
||||
|
||||
servos = new Servos(hardwareMap);
|
||||
|
||||
turret = new Turret(robot, TELE, robot.limelight);
|
||||
|
||||
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
|
||||
|
||||
light = Light.getInstance();
|
||||
|
||||
light.init(robot.light, spindexer, turret);
|
||||
|
||||
autoActions = new AutoActions(robot, drive, TELE, servos, flywheel, spindexer, targeting, targetingSettings, turret, light);
|
||||
|
||||
int motif = 21;
|
||||
boolean intaking = true;
|
||||
|
||||
waitForStart();
|
||||
if (isStopRequested()) return;
|
||||
|
||||
while (opModeIsActive()){
|
||||
spindexer.setIntakePower(1);
|
||||
robot.transfer.setPower(1);
|
||||
|
||||
if (gamepad1.crossWasPressed()){
|
||||
motif = 21;
|
||||
} else if (gamepad1.squareWasPressed()){
|
||||
motif = 22;
|
||||
} else if (gamepad1.triangleWasPressed()){
|
||||
motif = 23;
|
||||
}
|
||||
flywheel.manageFlywheel(2500);
|
||||
|
||||
if (gamepad1.leftBumperWasPressed()){
|
||||
intaking = false;
|
||||
Actions.runBlocking(
|
||||
autoActions.prepareShootAll(
|
||||
3,
|
||||
5,
|
||||
motif,
|
||||
0.501,
|
||||
0.501,
|
||||
0.501
|
||||
)
|
||||
);
|
||||
} else if (gamepad1.rightBumperWasPressed()){
|
||||
intaking = false;
|
||||
Actions.runBlocking(
|
||||
autoActions.shootAllAuto(
|
||||
3.5,
|
||||
0.014,
|
||||
0.501,
|
||||
0.501,
|
||||
0.501
|
||||
)
|
||||
);
|
||||
intaking = true;
|
||||
} else if (intaking){
|
||||
spindexer.processIntake();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -671,8 +671,10 @@ public class Spindexer {
|
||||
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.REARCENTER.ordinal()]].ballColor;
|
||||
}
|
||||
private double prevPow = 0.501;
|
||||
private boolean firstIntakePow = true;
|
||||
public void setIntakePower(double pow){
|
||||
if (prevPow != 0.501 && prevPow != pow){
|
||||
if (firstIntakePow || prevPow != pow){
|
||||
firstIntakePow = false;
|
||||
robot.intake.setPower(pow);
|
||||
}
|
||||
prevPow = pow;
|
||||
|
||||
@@ -14,6 +14,7 @@ import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
|
||||
import org.firstinspires.ftc.teamcode.constants.Color;
|
||||
|
||||
import java.util.ArrayList;
|
||||
import java.util.List;
|
||||
|
||||
@Config
|
||||
@@ -58,6 +59,9 @@ public class Turret {
|
||||
private int prevPipeline = -1;
|
||||
PIDController bearingPID;
|
||||
|
||||
public int llCoast = 0;
|
||||
public int LL_COAST_TICKS = 60;
|
||||
|
||||
public Turret(Robot rob, MultipleTelemetry tele, Limelight3A cam) {
|
||||
this.TELE = tele;
|
||||
this.robot = rob;
|
||||
@@ -130,7 +134,7 @@ public class Turret {
|
||||
}
|
||||
}
|
||||
if (xPos != null){
|
||||
if (zPos>0) {
|
||||
if (zPos<0) {
|
||||
limelightTagX = (alphaPosConstant * xPos) + ((1 - alphaPosConstant) * limelightTagX);
|
||||
limelightTagY = (alphaPosConstant * yPos) + ((1 - alphaPosConstant) * limelightTagY);
|
||||
limelightTagZ = (alphaPosConstant * zPos) + ((1 - alphaPosConstant) * limelightTagZ);
|
||||
@@ -171,8 +175,12 @@ public class Turret {
|
||||
LLResult result = webcam.getLatestResult();
|
||||
if (result != null && result.isValid()) {
|
||||
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||
double prevTx = -1000;
|
||||
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||
obeliskID = fiducial.getFiducialId();
|
||||
double currentTx = fiducial.getTargetXDegrees();
|
||||
if (currentTx > prevTx){
|
||||
obeliskID = fiducial.getFiducialId();
|
||||
}
|
||||
}
|
||||
}
|
||||
return obeliskID;
|
||||
@@ -266,11 +274,18 @@ public class Turret {
|
||||
|
||||
turretAngleDeg += permanentOffset;
|
||||
|
||||
|
||||
limelightRead();
|
||||
// Active correction if we see the target
|
||||
if (result.isValid() && !lockOffset && limelightUsed) {
|
||||
currentTrackOffset += bearingAlign(result);
|
||||
currentTrackCount++;
|
||||
|
||||
TELE.addData("LL Tracking: ", llCoast);
|
||||
|
||||
// Assume the last tracked value is always better than
|
||||
// any previous value, even if its not fully aligned.
|
||||
llCoast = LL_COAST_TICKS;
|
||||
// double bearingError = Math.abs(tagBearingDeg);
|
||||
//
|
||||
// if (bearingError > cameraBearingEqual) {
|
||||
@@ -301,9 +316,15 @@ public class Turret {
|
||||
// if (currentTrackCount > 20) {
|
||||
// offset = currentTrackOffset;
|
||||
// }
|
||||
lightColor = Color.LightRed;
|
||||
currentTrackOffset = 0.0;
|
||||
currentTrackCount = 0;
|
||||
if (llCoast <= 0) {
|
||||
TELE.addData("LL No Track: ", llCoast);
|
||||
lightColor = Color.LightRed;
|
||||
currentTrackOffset = 0.0;
|
||||
currentTrackCount = 0;
|
||||
} else {
|
||||
TELE.addData("LL Coasting: ", llCoast);
|
||||
llCoast--;
|
||||
}
|
||||
}
|
||||
|
||||
// Apply accumulated offset
|
||||
|
||||
@@ -6,7 +6,6 @@ repositories {
|
||||
maven { url = 'https://maven.brott.dev/' } //RR
|
||||
maven { url = "https://maven.rowanmcalpin.com/" } //Next FTC
|
||||
maven { url = "https://repo.dairy.foundation/releases" } //AS
|
||||
|
||||
}
|
||||
|
||||
dependencies {
|
||||
@@ -25,8 +24,6 @@ dependencies {
|
||||
implementation 'com.pedropathing:ftc:2.0.6' //PedroCore
|
||||
implementation 'com.pedropathing:telemetry:1.0.0' //PedroTele
|
||||
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
|
||||
|
||||
|
||||
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
|
||||
|
||||
implementation 'com.rowanmcalpin.nextftc:core:0.6.2' //NEXT FTC
|
||||
|
||||
Reference in New Issue
Block a user