Compare commits
31 Commits
7161933d06
...
master
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
7043274ebd | ||
|
|
bd05090afe | ||
|
|
369e379eb4 | ||
|
|
41853e9ad1 | ||
| c01edd9308 | |||
| ccfac3e123 | |||
| 395d4439db | |||
| 5f33cb4d41 | |||
| e92f11bc69 | |||
| 457eaf5feb | |||
| dc9886855b | |||
| 194100e3c8 | |||
| 64b2fed8d6 | |||
| 2ccd7f04f8 | |||
| 1ae4e1c3ed | |||
| 7a2b275e66 | |||
| 0264cf2c77 | |||
| f69bffc3ee | |||
| 09347ce479 | |||
| 102693d94a | |||
| c2e0b69c55 | |||
| 82c16b5402 | |||
| 5a456e211f | |||
| e87c5bb845 | |||
| a695f19cc6 | |||
| 1ad33fd45b | |||
| 56b61ee88b | |||
| 1ee40b472a | |||
| 3268d5cd02 | |||
| 44caad767b | |||
| dd1db74059 |
@@ -5,23 +5,37 @@ 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.blueObeliskTurrPos1;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos2;
|
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.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.redObeliskTurrPos1;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.redObeliskTurrPos2;
|
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.redObeliskTurrPos3;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
|
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.constants.ServoPositions.transferServo_out;
|
||||||
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
|
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
|
||||||
import static org.firstinspires.ftc.teamcode.utils.Turret.turrDefault;
|
import static org.firstinspires.ftc.teamcode.utils.Turret.turrDefault;
|
||||||
|
|
||||||
|
import androidx.annotation.NonNull;
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.FtcDashboard;
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
import com.acmerobotics.dashboard.config.Config;
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||||
|
import com.acmerobotics.roadrunner.Action;
|
||||||
import com.acmerobotics.roadrunner.ParallelAction;
|
import com.acmerobotics.roadrunner.ParallelAction;
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.acmerobotics.roadrunner.PoseVelocity2d;
|
||||||
|
import com.acmerobotics.roadrunner.SequentialAction;
|
||||||
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
|
||||||
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
||||||
import com.acmerobotics.roadrunner.Vector2d;
|
import com.acmerobotics.roadrunner.Vector2d;
|
||||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||||
|
import com.acmerobotics.roadrunner.ftc.PinpointIMU;
|
||||||
|
import com.qualcomm.hardware.gobilda.GoBildaPinpointDriver;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
@@ -39,20 +53,20 @@ import org.firstinspires.ftc.teamcode.utils.Turret;
|
|||||||
@Autonomous(preselectTeleOp = "TeleopV3")
|
@Autonomous(preselectTeleOp = "TeleopV3")
|
||||||
public class Auto_LT_Close extends LinearOpMode {
|
public class Auto_LT_Close extends LinearOpMode {
|
||||||
public static double shoot0Vel = 2300, shoot0Hood = 0.93;
|
public static double shoot0Vel = 2300, shoot0Hood = 0.93;
|
||||||
|
public static double velGate0Start = 2700, hoodGate0Start = 0.6;
|
||||||
|
|
||||||
|
public static double velGate0End = 2700, hoodGate0End = 0.35;
|
||||||
|
public static double hood0MoveTime = 2;
|
||||||
public static double spindexerSpeedIncrease = 0.014;
|
public static double spindexerSpeedIncrease = 0.014;
|
||||||
|
|
||||||
double obeliskTurrPos1 = 0.0;
|
public static double shootAllTime = 6.0;
|
||||||
double obeliskTurrPos2 = 0.0;
|
|
||||||
double obeliskTurrPos3 = 0.0;
|
|
||||||
|
|
||||||
public static double shootAllTime = 2;
|
|
||||||
public static double intake1Time = 3.3;
|
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 flywheel0Time = 1.9;
|
||||||
public static double pickup1Speed = 12;
|
public static double pickup1Speed = 14;
|
||||||
// ---- POSITION TOLERANCES ----
|
// ---- POSITION TOLERANCES ----
|
||||||
public static double posXTolerance = 5.0;
|
public static double posXTolerance = 5.0;
|
||||||
public static double posYTolerance = 5.0;
|
public static double posYTolerance = 5.0;
|
||||||
@@ -61,7 +75,23 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
public static double shoot2Time = 2.5;
|
public static double shoot2Time = 2.5;
|
||||||
public static double shoot3Time = 2.5;
|
public static double shoot3Time = 2.5;
|
||||||
public static double colorSenseTime = 1.2;
|
public static double colorSenseTime = 1.2;
|
||||||
public int motif = 0;
|
public static double waitToShoot0 = 0.5;
|
||||||
|
public static double waitToPickupGate2 = 0.3;
|
||||||
|
public static double pickupStackGateSpeed = 19;
|
||||||
|
public static double intake2TimeGate = 5;
|
||||||
|
public static double shoot2GateTime = 1.7;
|
||||||
|
public static double endGateTime = 22;
|
||||||
|
public static double waitToPickupGateWithPartner = 0.7;
|
||||||
|
public static double waitToPickupGateSolo = 0.01;
|
||||||
|
public static double intakeGateTime = 5.6;
|
||||||
|
public static double shootGateTime = 1.5;
|
||||||
|
public static double shoot1GateTime = 1.7;
|
||||||
|
public static double intake1GateTime = 3.3;
|
||||||
|
public static double lastShootTime = 27;
|
||||||
|
|
||||||
|
public static double openGateX = 26;
|
||||||
|
public static double openGateY = 48;
|
||||||
|
public static double openGateH = Math.toRadians(155);
|
||||||
|
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
@@ -74,8 +104,9 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
Targeting.Settings targetingSettings;
|
Targeting.Settings targetingSettings;
|
||||||
AutoActions autoActions;
|
AutoActions autoActions;
|
||||||
Light light;
|
Light light;
|
||||||
double x1, y1, h1;
|
|
||||||
|
|
||||||
|
int motif = 0;
|
||||||
|
double x1, y1, h1;
|
||||||
double x2a, y2a, h2a, t2a;
|
double x2a, y2a, h2a, t2a;
|
||||||
|
|
||||||
double x2b, y2b, h2b, t2b;
|
double x2b, y2b, h2b, t2b;
|
||||||
@@ -87,13 +118,22 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
double x4b, y4b, h4b;
|
double x4b, y4b, h4b;
|
||||||
|
|
||||||
double xShoot, yShoot, hShoot;
|
double xShoot, yShoot, hShoot;
|
||||||
double xGate, yGate, hGate;
|
double xShoot0, yShoot0, hShoot0;
|
||||||
double xPrep, yPrep, hPrep;
|
double pickupGateAX, pickupGateAY, pickupGateAH;
|
||||||
|
double pickupGateBX, pickupGateBY, pickupGateBH;
|
||||||
|
double xShootGate, yShootGate, hShootGate;
|
||||||
double xLeave, yLeave, hLeave;
|
double xLeave, yLeave, hLeave;
|
||||||
|
double xLeaveGate, yLeaveGate, hLeaveGate;
|
||||||
|
|
||||||
int ballCycles = 3;
|
int ballCycles = 3;
|
||||||
int prevMotif = 0;
|
int prevMotif = 0;
|
||||||
|
boolean gateCycle = true;
|
||||||
|
boolean withPartner = true;
|
||||||
|
double obeliskTurrPos1 = 0.0;
|
||||||
|
double obeliskTurrPos2 = 0.0;
|
||||||
|
double obeliskTurrPos3 = 0.0;
|
||||||
|
double waitToPickupGate = 0;
|
||||||
|
double obeliskTurrPosAutoStart = 0;
|
||||||
|
|
||||||
// initialize path variables here
|
// initialize path variables here
|
||||||
TrajectoryActionBuilder shoot0 = null;
|
TrajectoryActionBuilder shoot0 = null;
|
||||||
@@ -103,6 +143,9 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
TrajectoryActionBuilder shoot2 = null;
|
TrajectoryActionBuilder shoot2 = null;
|
||||||
TrajectoryActionBuilder pickup3 = null;
|
TrajectoryActionBuilder pickup3 = null;
|
||||||
TrajectoryActionBuilder shoot3 = null;
|
TrajectoryActionBuilder shoot3 = null;
|
||||||
|
TrajectoryActionBuilder shoot0ToPickup2 = null;
|
||||||
|
TrajectoryActionBuilder gateCyclePickup = null;
|
||||||
|
TrajectoryActionBuilder gateCycleShoot = null;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
@@ -132,18 +175,51 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
|
|
||||||
autoActions = new AutoActions(robot, drive, TELE, servos, flywheel, spindexer, targeting, targetingSettings, turret, light);
|
autoActions = new AutoActions(robot, drive, TELE, servos, flywheel, spindexer, targeting, targetingSettings, turret, light);
|
||||||
|
|
||||||
servos.setSpinPos(spinStartPos);
|
servos.setSpinPos(spindexer_intakePos1);
|
||||||
|
|
||||||
servos.setTransferPos(transferServo_out);
|
servos.setTransferPos(transferServo_out);
|
||||||
|
|
||||||
limelightUsed = false;
|
limelightUsed = false;
|
||||||
|
|
||||||
robot.light.setPosition(1);
|
robot.light.setPosition(1);
|
||||||
|
|
||||||
while (opModeInInit()) {
|
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);
|
||||||
|
} else {
|
||||||
servos.setHoodPos(shoot0Hood);
|
servos.setHoodPos(shoot0Hood);
|
||||||
turret.setTurret(turrDefault);
|
}
|
||||||
|
|
||||||
if (gamepad2.crossWasPressed()) {
|
if (gamepad2.crossWasPressed()) {
|
||||||
redAlliance = !redAlliance;
|
redAlliance = !redAlliance;
|
||||||
@@ -164,9 +240,18 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
ballCycles--;
|
ballCycles--;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (gamepad2.triangleWasPressed()){
|
||||||
|
gateCycle = !gateCycle;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
if (gamepad2.squareWasPressed()) {
|
if (gamepad2.squareWasPressed()) {
|
||||||
turret.pipelineSwitch(1);
|
|
||||||
|
drive = new MecanumDrive(hardwareMap,new Pose2d(0,0,0));
|
||||||
robot.limelight.start();
|
robot.limelight.start();
|
||||||
|
limelightUsed = true;
|
||||||
|
|
||||||
gamepad2.rumble(500);
|
gamepad2.rumble(500);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -197,9 +282,7 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
x4b = rx4b;
|
x4b = rx4b;
|
||||||
y4b = ry4b;
|
y4b = ry4b;
|
||||||
h4b = rh4b;
|
h4b = rh4b;
|
||||||
xPrep = rxPrep;
|
|
||||||
yPrep = ryPrep;
|
|
||||||
hPrep = rhPrep;
|
|
||||||
xShoot = rShootX;
|
xShoot = rShootX;
|
||||||
yShoot = rShootY;
|
yShoot = rShootY;
|
||||||
hShoot = rShootH;
|
hShoot = rShootH;
|
||||||
@@ -207,6 +290,24 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
yLeave = rLeaveY;
|
yLeave = rLeaveY;
|
||||||
hLeave = rLeaveH;
|
hLeave = rLeaveH;
|
||||||
|
|
||||||
|
xShoot0 = rShoot0X;
|
||||||
|
yShoot0 = rShoot0Y;
|
||||||
|
hShoot0 = rShoot0H;
|
||||||
|
xShootGate = rShootGateX;
|
||||||
|
yShootGate = rShootGateY;
|
||||||
|
hShootGate = rShootGateH;
|
||||||
|
xLeaveGate = rLeaveGateX;
|
||||||
|
yLeaveGate = rLeaveGateY;
|
||||||
|
hLeaveGate = rLeaveGateH;
|
||||||
|
|
||||||
|
pickupGateAX = rPickupGateAX;
|
||||||
|
pickupGateAY = rPickupGateAY;
|
||||||
|
pickupGateAH = rPickupGateAH;
|
||||||
|
pickupGateBX = rPickupGateBX;
|
||||||
|
pickupGateBY = rPickupGateBY;
|
||||||
|
pickupGateBH = rPickupGateBH;
|
||||||
|
|
||||||
|
obeliskTurrPosAutoStart = turrDefault + redObeliskTurrPos0;
|
||||||
obeliskTurrPos1 = turrDefault + redObeliskTurrPos1;
|
obeliskTurrPos1 = turrDefault + redObeliskTurrPos1;
|
||||||
obeliskTurrPos2 = turrDefault + redObeliskTurrPos2;
|
obeliskTurrPos2 = turrDefault + redObeliskTurrPos2;
|
||||||
obeliskTurrPos3 = turrDefault + redObeliskTurrPos3;
|
obeliskTurrPos3 = turrDefault + redObeliskTurrPos3;
|
||||||
@@ -238,9 +339,6 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
y4b = by4b;
|
y4b = by4b;
|
||||||
h4b = bh4b;
|
h4b = bh4b;
|
||||||
|
|
||||||
xPrep = bxPrep;
|
|
||||||
yPrep = byPrep;
|
|
||||||
hPrep = bhPrep;
|
|
||||||
xShoot = bShootX;
|
xShoot = bShootX;
|
||||||
yShoot = bShootY;
|
yShoot = bShootY;
|
||||||
hShoot = bShootH;
|
hShoot = bShootH;
|
||||||
@@ -248,20 +346,93 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
yLeave = bLeaveY;
|
yLeave = bLeaveY;
|
||||||
hLeave = bLeaveH;
|
hLeave = bLeaveH;
|
||||||
|
|
||||||
|
xShoot0 = bShoot0X;
|
||||||
|
yShoot0 = bShoot0Y;
|
||||||
|
hShoot0 = bShoot0H;
|
||||||
|
xShootGate = bShootGateX;
|
||||||
|
yShootGate = bShootGateY;
|
||||||
|
hShootGate = bShootGateH;
|
||||||
|
xLeaveGate = bLeaveGateX;
|
||||||
|
yLeaveGate = bLeaveGateY;
|
||||||
|
hLeaveGate = bLeaveGateH;
|
||||||
|
|
||||||
|
pickupGateAX = bPickupGateAX;
|
||||||
|
pickupGateAY = bPickupGateAY;
|
||||||
|
pickupGateAH = bPickupGateAH;
|
||||||
|
pickupGateBX = bPickupGateBX;
|
||||||
|
pickupGateBY = bPickupGateBY;
|
||||||
|
pickupGateBH = bPickupGateBH;
|
||||||
|
|
||||||
|
obeliskTurrPosAutoStart = turrDefault + redObeliskTurrPos0;
|
||||||
obeliskTurrPos1 = turrDefault + blueObeliskTurrPos1;
|
obeliskTurrPos1 = turrDefault + blueObeliskTurrPos1;
|
||||||
obeliskTurrPos2 = turrDefault + blueObeliskTurrPos2;
|
obeliskTurrPos2 = turrDefault + blueObeliskTurrPos2;
|
||||||
obeliskTurrPos3 = turrDefault + blueObeliskTurrPos3;
|
obeliskTurrPos3 = turrDefault + blueObeliskTurrPos3;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (gateCycle) {
|
||||||
|
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
|
.strafeToLinearHeading(new Vector2d(xShoot0, yShoot0), Math.toRadians(hShoot0));
|
||||||
|
} else {
|
||||||
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
|
||||||
.strafeToLinearHeading(new Vector2d(x1, y1), Math.toRadians(h1));
|
.strafeToLinearHeading(new Vector2d(x1, y1), Math.toRadians(h1));
|
||||||
|
}
|
||||||
|
|
||||||
|
if (gateCycle) {
|
||||||
|
pickup2 = shoot0.endTrajectory().fresh()
|
||||||
|
.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&& withPartner) {
|
||||||
|
shoot2 = pickup2.endTrajectory().fresh()
|
||||||
|
.strafeToLinearHeading(new Vector2d(openGateX, openGateY), Math.toRadians(openGateH))
|
||||||
|
.strafeToLinearHeading(new Vector2d(xShootGate, yShootGate), Math.toRadians(pickupGateAH));
|
||||||
|
} else if (gateCycle) {
|
||||||
|
shoot2 = pickup2.endTrajectory().fresh()
|
||||||
|
.strafeToLinearHeading(new Vector2d(xShootGate, yShootGate), Math.toRadians(hShootGate));
|
||||||
|
} else if (ballCycles < 3) {
|
||||||
|
shoot2 = drive.actionBuilder(new Pose2d(x3b, y3b, Math.toRadians(h3b)))
|
||||||
|
.strafeToLinearHeading(new Vector2d(xLeave, yLeave), Math.toRadians(hLeave));
|
||||||
|
} else {
|
||||||
|
shoot2 = drive.actionBuilder(new Pose2d(x3b, y3b, Math.toRadians(h3b)))
|
||||||
|
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), Math.toRadians(hShoot));
|
||||||
|
}
|
||||||
|
|
||||||
|
gateCyclePickup = shoot2.endTrajectory().fresh()
|
||||||
|
.strafeToLinearHeading(new Vector2d(pickupGateAX, pickupGateAY), Math.toRadians(pickupGateAH))
|
||||||
|
.waitSeconds(waitToPickupGate)
|
||||||
|
.strafeToLinearHeading(new Vector2d(pickupGateBX, pickupGateBY), Math.toRadians(pickupGateBH))
|
||||||
|
.waitSeconds(0.1)
|
||||||
|
.strafeToLinearHeading(new Vector2d(pickupGateCX, pickupGateCY), Math.toRadians(pickupGateCH),
|
||||||
|
new TranslationalVelConstraint(13));
|
||||||
|
|
||||||
|
gateCycleShoot = gateCyclePickup.endTrajectory().fresh()
|
||||||
|
.strafeToLinearHeading(new Vector2d(xShootGate, yShootGate), Math.toRadians(hShootGate));
|
||||||
|
|
||||||
|
|
||||||
|
if (gateCycle) {
|
||||||
|
pickup1 = gateCycleShoot.endTrajectory().fresh()
|
||||||
|
.strafeToLinearHeading(new Vector2d(x2a, y2a), Math.toRadians(h2a))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x2b, y2b), Math.toRadians(h2b),
|
||||||
|
new TranslationalVelConstraint(pickupStackGateSpeed));
|
||||||
|
} else {
|
||||||
pickup1 = drive.actionBuilder(new Pose2d(x1, y1, Math.toRadians(h1)))
|
pickup1 = drive.actionBuilder(new Pose2d(x1, y1, Math.toRadians(h1)))
|
||||||
.strafeToLinearHeading(new Vector2d(x2a, y2a), Math.toRadians(h2a))
|
.strafeToLinearHeading(new Vector2d(x2a, y2a), Math.toRadians(h2a))
|
||||||
.strafeToLinearHeading(new Vector2d(x2b, y2b), Math.toRadians(h2b),
|
.strafeToLinearHeading(new Vector2d(x2b, y2b), Math.toRadians(h2b),
|
||||||
new TranslationalVelConstraint(pickup1Speed));
|
new TranslationalVelConstraint(pickup1Speed));
|
||||||
|
}
|
||||||
|
|
||||||
if (ballCycles < 2){
|
|
||||||
|
if (gateCycle) {
|
||||||
|
shoot1 = pickup1.endTrajectory().fresh()
|
||||||
|
.strafeToLinearHeading(new Vector2d(xLeaveGate, yLeaveGate), Math.toRadians(hLeaveGate));
|
||||||
|
} else if (ballCycles < 2) {
|
||||||
shoot1 = drive.actionBuilder(new Pose2d(x2b, y2b, Math.toRadians(h2b)))
|
shoot1 = drive.actionBuilder(new Pose2d(x2b, y2b, Math.toRadians(h2b)))
|
||||||
.strafeToLinearHeading(new Vector2d(xLeave, yLeave), Math.toRadians(hLeave));
|
.strafeToLinearHeading(new Vector2d(xLeave, yLeave), Math.toRadians(hLeave));
|
||||||
} else {
|
} else {
|
||||||
@@ -269,19 +440,6 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), Math.toRadians(hShoot));
|
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), Math.toRadians(hShoot));
|
||||||
}
|
}
|
||||||
|
|
||||||
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 (ballCycles < 3){
|
|
||||||
shoot2 = drive.actionBuilder(new Pose2d(x3b, y3b, Math.toRadians(h3b)))
|
|
||||||
.strafeToLinearHeading(new Vector2d(xLeave, yLeave), Math.toRadians(hLeave));
|
|
||||||
} else {
|
|
||||||
shoot2 = drive.actionBuilder(new Pose2d(x3b, y3b, Math.toRadians(h3b)))
|
|
||||||
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), Math.toRadians(hLeave));
|
|
||||||
}
|
|
||||||
|
|
||||||
pickup3 = drive.actionBuilder(new Pose2d(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(x4a, y4a), Math.toRadians(h4a))
|
||||||
.strafeToLinearHeading(new Vector2d(x4b, y4b), Math.toRadians(h4b),
|
.strafeToLinearHeading(new Vector2d(x4b, y4b), Math.toRadians(h4b),
|
||||||
@@ -290,9 +448,19 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
shoot3 = drive.actionBuilder(new Pose2d(x4b, y4b, Math.toRadians(h4b)))
|
shoot3 = drive.actionBuilder(new Pose2d(x4b, y4b, Math.toRadians(h4b)))
|
||||||
.strafeToLinearHeading(new Vector2d(xLeave, yLeave), Math.toRadians(hLeave));
|
.strafeToLinearHeading(new Vector2d(xLeave, yLeave), Math.toRadians(hLeave));
|
||||||
|
|
||||||
|
if (withPartner) {
|
||||||
|
waitToPickupGate = waitToPickupGateWithPartner;
|
||||||
|
} else {
|
||||||
|
waitToPickupGate = waitToPickupGateSolo;
|
||||||
|
}
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
TELE.addData("Red?", redAlliance);
|
TELE.addData("Red?", redAlliance);
|
||||||
TELE.addData("Turret Default", turrDefault);
|
TELE.addData("Turret Default", turrDefault);
|
||||||
|
TELE.addData("Gate Cycle?", gateCycle);
|
||||||
TELE.addData("Ball Cycles", ballCycles);
|
TELE.addData("Ball Cycles", ballCycles);
|
||||||
|
TELE.addData("Limelight Started?", limelightUsed);
|
||||||
|
TELE.addData("Motif", motif);
|
||||||
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
}
|
}
|
||||||
@@ -303,24 +471,53 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
|
|
||||||
if (opModeIsActive()) {
|
if (opModeIsActive()) {
|
||||||
|
|
||||||
|
double stamp = getRuntime();
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
|
||||||
|
if (gateCycle) {
|
||||||
|
startAutoGate();
|
||||||
|
shoot(0.501, 0.501, 0.501);
|
||||||
|
cycleStackMiddleGate();
|
||||||
|
shoot(0.501,0.501, 0.501);
|
||||||
|
|
||||||
|
while (getRuntime() - stamp < endGateTime) {
|
||||||
|
cycleGateIntake();
|
||||||
|
if (getRuntime() - stamp < lastShootTime) {
|
||||||
|
cycleGateShoot();
|
||||||
|
shoot(0.501, 0.501, 0.501);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
cycleStackCloseIntakeGate();
|
||||||
|
|
||||||
|
if (getRuntime() - stamp < lastShootTime) {
|
||||||
|
cycleStackCloseShootGate();
|
||||||
|
}
|
||||||
|
|
||||||
|
shoot(0.501, 0.501, 0.501);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
startAuto();
|
startAuto();
|
||||||
shoot();
|
shoot(0.501, 0.501,0.501);
|
||||||
|
|
||||||
if (ballCycles > 0) {
|
if (ballCycles > 0) {
|
||||||
cycleStackClose();
|
cycleStackClose();
|
||||||
shoot();
|
shoot(xShoot, yShoot, hShoot);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (ballCycles > 1) {
|
if (ballCycles > 1) {
|
||||||
cycleStackMiddle();
|
cycleStackMiddle();
|
||||||
shoot();
|
shoot(xShoot, yShoot, hShoot);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (ballCycles > 2) {
|
if (ballCycles > 2) {
|
||||||
cycleStackFar();
|
cycleStackFar();
|
||||||
shoot();
|
shoot(xLeave, yLeave, hLeave);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
while (opModeIsActive()) {
|
while (opModeIsActive()) {
|
||||||
@@ -340,13 +537,8 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void shoot(){
|
void shoot(double x, double y, double z) {
|
||||||
Actions.runBlocking(
|
Actions.runBlocking(autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease, x, y, z));
|
||||||
new ParallelAction(
|
|
||||||
autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease)
|
|
||||||
)
|
|
||||||
|
|
||||||
);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void startAuto() {
|
void startAuto() {
|
||||||
@@ -355,14 +547,39 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
Actions.runBlocking(
|
Actions.runBlocking(
|
||||||
new ParallelAction(
|
new ParallelAction(
|
||||||
shoot0.build(),
|
shoot0.build(),
|
||||||
autoActions.manageShooterAuto(
|
autoActions.prepareShootAll(
|
||||||
|
0.8,
|
||||||
flywheel0Time,
|
flywheel0Time,
|
||||||
|
motif,
|
||||||
x1,
|
x1,
|
||||||
y1,
|
y1,
|
||||||
h1
|
h1
|
||||||
)
|
)
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void startAutoGate() {
|
||||||
|
assert shoot0 != null;
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot0.build(),
|
||||||
|
autoActions.prepareShootAll(
|
||||||
|
colorSenseTime,
|
||||||
|
flywheel0Time,
|
||||||
|
motif,
|
||||||
|
xShoot0,
|
||||||
|
yShoot0,
|
||||||
|
hShoot0
|
||||||
|
)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void cycleStackClose() {
|
void cycleStackClose() {
|
||||||
@@ -374,24 +591,10 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
x2b,
|
x2b,
|
||||||
y2b,
|
y2b,
|
||||||
h2b
|
h2b
|
||||||
),
|
|
||||||
autoActions.detectObelisk(
|
|
||||||
intake1Time,
|
|
||||||
x2b,
|
|
||||||
y2b,
|
|
||||||
posXTolerance,
|
|
||||||
posYTolerance,
|
|
||||||
obeliskTurrPos1
|
|
||||||
)
|
)
|
||||||
|
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
|
|
||||||
motif = turret.getObeliskID();
|
|
||||||
|
|
||||||
if (motif == 0) motif = 22;
|
|
||||||
prevMotif = motif;
|
|
||||||
|
|
||||||
double posX;
|
double posX;
|
||||||
double posY;
|
double posY;
|
||||||
double posH;
|
double posH;
|
||||||
@@ -429,24 +632,10 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
x3b,
|
x3b,
|
||||||
y3b,
|
y3b,
|
||||||
h3b
|
h3b
|
||||||
),
|
|
||||||
autoActions.detectObelisk(
|
|
||||||
intake2Time,
|
|
||||||
x3b,
|
|
||||||
y3b,
|
|
||||||
posXTolerance,
|
|
||||||
posYTolerance,
|
|
||||||
obeliskTurrPos2
|
|
||||||
)
|
)
|
||||||
|
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
|
|
||||||
motif = turret.getObeliskID();
|
|
||||||
|
|
||||||
if (motif == 0) motif = prevMotif;
|
|
||||||
prevMotif = motif;
|
|
||||||
|
|
||||||
double posX;
|
double posX;
|
||||||
double posY;
|
double posY;
|
||||||
double posH;
|
double posH;
|
||||||
@@ -483,16 +672,7 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
x4b,
|
x4b,
|
||||||
y4b,
|
y4b,
|
||||||
h4b
|
h4b
|
||||||
),
|
|
||||||
autoActions.detectObelisk(
|
|
||||||
intake3Time,
|
|
||||||
x4b,
|
|
||||||
y4b,
|
|
||||||
posXTolerance,
|
|
||||||
posYTolerance,
|
|
||||||
obeliskTurrPos3
|
|
||||||
)
|
)
|
||||||
|
|
||||||
)
|
)
|
||||||
);
|
);
|
||||||
|
|
||||||
@@ -515,4 +695,118 @@ public class Auto_LT_Close extends LinearOpMode {
|
|||||||
)
|
)
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void cycleStackMiddleGate() {
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
pickup2 = drive.actionBuilder(drive.localizer.getPose())
|
||||||
|
.strafeToLinearHeading(new Vector2d(x3a, y3a), Math.toRadians(h3a))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x3b, y3b), Math.toRadians(h3b),
|
||||||
|
new TranslationalVelConstraint(pickupStackGateSpeed));
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup2.build(),
|
||||||
|
autoActions.intake(
|
||||||
|
intake2TimeGate,
|
||||||
|
x3b,
|
||||||
|
y3b,
|
||||||
|
h3b
|
||||||
|
)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
|
servos.setSpinPos(spinStartPos);
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot2.build(),
|
||||||
|
autoActions.prepareShootAll(
|
||||||
|
colorSenseTime,
|
||||||
|
shoot2Time,
|
||||||
|
motif,
|
||||||
|
xShootGate,
|
||||||
|
yShootGate,
|
||||||
|
pickupGateAH)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
void cycleGateIntake() {
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
gateCyclePickup.build(),
|
||||||
|
autoActions.intake(
|
||||||
|
intakeGateTime,
|
||||||
|
xShootGate,
|
||||||
|
yShootGate,
|
||||||
|
hShootGate
|
||||||
|
)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
void cycleGateShoot() {
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
servos.setSpinPos(spinStartPos);
|
||||||
|
|
||||||
|
gateCycleShoot = drive.actionBuilder(drive.localizer.getPose())
|
||||||
|
.strafeToLinearHeading(new Vector2d(xShootGate, yShootGate), Math.toRadians(pickupGateAH));
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
gateCycleShoot.build(),
|
||||||
|
autoActions.manageShooterAuto(
|
||||||
|
shootGateTime,
|
||||||
|
xShootGate,
|
||||||
|
yShootGate,
|
||||||
|
pickupGateAH,
|
||||||
|
false
|
||||||
|
)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
void cycleStackCloseIntakeGate() {
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
pickup1 = drive.actionBuilder(drive.localizer.getPose())
|
||||||
|
.strafeToLinearHeading(new Vector2d(x2a, y2a), Math.toRadians(h2a))
|
||||||
|
.strafeToLinearHeading(new Vector2d(x2b, y2b), Math.toRadians(h2b),
|
||||||
|
new TranslationalVelConstraint(pickupStackGateSpeed));
|
||||||
|
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
pickup1.build(),
|
||||||
|
autoActions.intake(
|
||||||
|
intake1GateTime,
|
||||||
|
xShootGate,
|
||||||
|
yShootGate,
|
||||||
|
hShootGate
|
||||||
|
)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
void cycleStackCloseShootGate(){
|
||||||
|
servos.setSpinPos(spinStartPos);
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
shoot1 = drive.actionBuilder(drive.localizer.getPose())
|
||||||
|
.strafeToLinearHeading(new Vector2d(xLeaveGate, yLeaveGate), Math.toRadians(hLeaveGate));
|
||||||
|
|
||||||
|
Actions.runBlocking(
|
||||||
|
new ParallelAction(
|
||||||
|
shoot1.build(),
|
||||||
|
autoActions.manageShooterAuto(
|
||||||
|
shoot1GateTime,
|
||||||
|
xLeaveGate,
|
||||||
|
yLeaveGate,
|
||||||
|
hLeaveGate,
|
||||||
|
false
|
||||||
|
)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
@@ -63,7 +63,7 @@ public class Auto_LT_Far extends LinearOpMode {
|
|||||||
boolean stack3 = true;
|
boolean stack3 = true;
|
||||||
double xStackPickupA, yStackPickupA, hStackPickupA;
|
double xStackPickupA, yStackPickupA, hStackPickupA;
|
||||||
double xStackPickupB, yStackPickupB, hStackPickupB;
|
double xStackPickupB, yStackPickupB, hStackPickupB;
|
||||||
public static int pickupStackSpeed = 12;
|
public static int pickupStackSpeed = 17;
|
||||||
public static int pickupGateSpeed = 25;
|
public static int pickupGateSpeed = 25;
|
||||||
int prevMotif = 0;
|
int prevMotif = 0;
|
||||||
public static double spindexerSpeedIncrease = 0.014;
|
public static double spindexerSpeedIncrease = 0.014;
|
||||||
@@ -74,8 +74,8 @@ public class Auto_LT_Far extends LinearOpMode {
|
|||||||
public static double shootStackTime = 2;
|
public static double shootStackTime = 2;
|
||||||
public static double shootGateTime = 2.5;
|
public static double shootGateTime = 2.5;
|
||||||
public static double colorSenseTime = 1;
|
public static double colorSenseTime = 1;
|
||||||
public static double intakeStackTime = 2.5;
|
public static double intakeStackTime = 4.5;
|
||||||
public static double intakeGateTime = 2;
|
public static double intakeGateTime = 8;
|
||||||
double obeliskTurrPos1 = 0.0;
|
double obeliskTurrPos1 = 0.0;
|
||||||
double obeliskTurrPos2 = 0.0;
|
double obeliskTurrPos2 = 0.0;
|
||||||
double obeliskTurrPos3 = 0.0;
|
double obeliskTurrPos3 = 0.0;
|
||||||
@@ -184,6 +184,8 @@ public class Auto_LT_Far extends LinearOpMode {
|
|||||||
if (gamepad2.squareWasPressed()){
|
if (gamepad2.squareWasPressed()){
|
||||||
turret.pipelineSwitch(4);
|
turret.pipelineSwitch(4);
|
||||||
robot.limelight.start();
|
robot.limelight.start();
|
||||||
|
drive = new MecanumDrive(hardwareMap,new Pose2d(0,0,0));
|
||||||
|
|
||||||
gamepad2.rumble(500);
|
gamepad2.rumble(500);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
@@ -221,6 +223,8 @@ public class Auto_LT_Far extends LinearOpMode {
|
|||||||
if (gamepad2.squareWasPressed()){
|
if (gamepad2.squareWasPressed()){
|
||||||
turret.pipelineSwitch(2);
|
turret.pipelineSwitch(2);
|
||||||
robot.limelight.start();
|
robot.limelight.start();
|
||||||
|
drive = new MecanumDrive(hardwareMap,new Pose2d(0,0,0));
|
||||||
|
|
||||||
gamepad2.rumble(500);
|
gamepad2.rumble(500);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -240,7 +244,10 @@ public class Auto_LT_Far extends LinearOpMode {
|
|||||||
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), Math.toRadians(hShoot));
|
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), Math.toRadians(hShoot));
|
||||||
|
|
||||||
pickupGate = drive.actionBuilder(new Pose2d(xShoot, yShoot, Math.toRadians(hShoot)))
|
pickupGate = drive.actionBuilder(new Pose2d(xShoot, yShoot, Math.toRadians(hShoot)))
|
||||||
.strafeToLinearHeading(new Vector2d(pickupGateX, pickupGateY), Math.toRadians(pickupGateH),
|
.strafeToLinearHeading(new Vector2d(pickupGateX, pickupGateY), Math.toRadians(pickupGateH))
|
||||||
|
.waitSeconds(0.2)
|
||||||
|
.strafeToLinearHeading(new Vector2d(pickupGateXB, pickupGateYB), Math.toRadians(pickupGateHB))
|
||||||
|
.strafeToLinearHeading(new Vector2d(pickupGateXC, pickupGateYC), Math.toRadians(pickupGateHC),
|
||||||
new TranslationalVelConstraint(pickupGateSpeed));
|
new TranslationalVelConstraint(pickupGateSpeed));
|
||||||
|
|
||||||
shootGate = drive.actionBuilder(new Pose2d(pickupGateX, pickupGateY, Math.toRadians(pickupGateH)))
|
shootGate = drive.actionBuilder(new Pose2d(pickupGateX, pickupGateY, Math.toRadians(pickupGateH)))
|
||||||
@@ -314,7 +321,7 @@ public class Auto_LT_Far extends LinearOpMode {
|
|||||||
void shoot(){
|
void shoot(){
|
||||||
Actions.runBlocking(
|
Actions.runBlocking(
|
||||||
new ParallelAction(
|
new ParallelAction(
|
||||||
autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease)
|
autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease, 0.501, 0.501, 0.501)
|
||||||
)
|
)
|
||||||
|
|
||||||
);
|
);
|
||||||
@@ -327,7 +334,8 @@ public class Auto_LT_Far extends LinearOpMode {
|
|||||||
flywheel0Time,
|
flywheel0Time,
|
||||||
0.501,
|
0.501,
|
||||||
0.501,
|
0.501,
|
||||||
0.501
|
0.501,
|
||||||
|
true
|
||||||
)
|
)
|
||||||
|
|
||||||
)
|
)
|
||||||
|
|||||||
@@ -2,6 +2,7 @@ package org.firstinspires.ftc.teamcode.autonomous.actions;
|
|||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
|
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
|
||||||
|
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_intakePos1;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
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_outtakeBall2;
|
||||||
@@ -17,7 +18,10 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
|||||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||||
import com.acmerobotics.roadrunner.Action;
|
import com.acmerobotics.roadrunner.Action;
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
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.ServoPositions;
|
||||||
import org.firstinspires.ftc.teamcode.constants.StateEnums;
|
import org.firstinspires.ftc.teamcode.constants.StateEnums;
|
||||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
@@ -47,7 +51,7 @@ public class AutoActions{
|
|||||||
private int passengerSlotGreen = 0;
|
private int passengerSlotGreen = 0;
|
||||||
private int rearSlotGreen = 0;
|
private int rearSlotGreen = 0;
|
||||||
private int mostGreenSlot = 0;
|
private int mostGreenSlot = 0;
|
||||||
private double firstSpindexShootPos = spindexer_outtakeBall1;
|
public static double firstSpindexShootPos = spinStartPos;
|
||||||
private boolean shootForward = true;
|
private boolean shootForward = true;
|
||||||
public int motif = 0;
|
public int motif = 0;
|
||||||
double spinEndPos = ServoPositions.spinEndPos;
|
double spinEndPos = ServoPositions.spinEndPos;
|
||||||
@@ -84,13 +88,13 @@ public class AutoActions{
|
|||||||
void spin1PosFirst() {
|
void spin1PosFirst() {
|
||||||
firstSpindexShootPos = spindexer_outtakeBall1;
|
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||||
shootForward = true;
|
shootForward = true;
|
||||||
spinEndPos = spindexer_outtakeBall3 + 0.1;
|
spinEndPos = 0.95;
|
||||||
}
|
}
|
||||||
|
|
||||||
void spin2PosFirst() {
|
void spin2PosFirst() {
|
||||||
firstSpindexShootPos = spindexer_outtakeBall2;
|
firstSpindexShootPos = spindexer_outtakeBall2;
|
||||||
shootForward = false;
|
shootForward = false;
|
||||||
spinEndPos = spindexer_outtakeBall3b - 0.1;
|
spinEndPos = 0.05;
|
||||||
}
|
}
|
||||||
|
|
||||||
void reverseSpin2PosFirst() {
|
void reverseSpin2PosFirst() {
|
||||||
@@ -102,21 +106,25 @@ public class AutoActions{
|
|||||||
void spin3PosFirst() {
|
void spin3PosFirst() {
|
||||||
firstSpindexShootPos = spindexer_outtakeBall3;
|
firstSpindexShootPos = spindexer_outtakeBall3;
|
||||||
shootForward = false;
|
shootForward = false;
|
||||||
spinEndPos = spindexer_outtakeBall1 - 0.1;
|
spinEndPos = 0.05;
|
||||||
}
|
}
|
||||||
|
|
||||||
void oddSpin3PosFirst() {
|
void oddSpin3PosFirst() {
|
||||||
firstSpindexShootPos = spindexer_outtakeBall3b;
|
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||||
shootForward = true;
|
shootForward = true;
|
||||||
spinEndPos = spindexer_outtakeBall2 + 0.1;
|
spinEndPos = 0.95;
|
||||||
}
|
}
|
||||||
|
|
||||||
Action manageShooter = null;
|
Action manageShooter = null;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
if (ticker == 0) {
|
if (ticker == 0) {
|
||||||
stamp = System.currentTimeMillis();
|
stamp = System.currentTimeMillis();
|
||||||
manageShooter = manageShooterAuto(time, posX, posY, posH);
|
manageShooter = manageShooterAuto(time, posX, posY, posH, false);
|
||||||
|
driverSlotGreen = 0;
|
||||||
|
passengerSlotGreen = 0;
|
||||||
|
rearSlotGreen = 0;
|
||||||
}
|
}
|
||||||
ticker++;
|
ticker++;
|
||||||
servos.setTransferPos(transferServo_out);
|
servos.setTransferPos(transferServo_out);
|
||||||
@@ -128,27 +136,50 @@ public class AutoActions{
|
|||||||
|
|
||||||
manageShooter.run(telemetryPacket);
|
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)) {
|
if ((System.currentTimeMillis() - stamp) < (colorSenseTime * 1000)) {
|
||||||
|
|
||||||
spindexerWiggle *= -1.0;
|
spindexerWiggle *= -1.0;
|
||||||
|
|
||||||
servos.setSpinPos(spindexer_intakePos1 + spindexerWiggle);
|
servos.setSpinPos(spindexer_intakePos1 + spindexerWiggle);
|
||||||
|
|
||||||
spindexer.detectBalls(true, true);
|
|
||||||
|
|
||||||
if (Objects.equals(spindexer.GetFrontDriverColor(), Spindexer.BallColor.GREEN)) {
|
// Rear Center (Position 1)
|
||||||
driverSlotGreen++;
|
double distanceRearCenter = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
}
|
if (distanceRearCenter < 52) {
|
||||||
|
NormalizedRGBA color1RGBA = robot.color1.getNormalizedColors();
|
||||||
if (Objects.equals(spindexer.GetFrontPassengerColor(), Spindexer.BallColor.GREEN)) {
|
double gP1 = color1RGBA.green / (color1RGBA.green + color1RGBA.red + color1RGBA.blue);
|
||||||
passengerSlotGreen++;
|
if (gP1 >= 0.38) {
|
||||||
}
|
|
||||||
|
|
||||||
if (Objects.equals(spindexer.GetRearCenterColor(), Spindexer.BallColor.GREEN)) {
|
|
||||||
rearSlotGreen++;
|
rearSlotGreen++;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
spindexer.setIntakePower(1);
|
// 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++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// 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(-0.1);
|
||||||
|
|
||||||
decideGreenSlot = true;
|
decideGreenSlot = true;
|
||||||
|
|
||||||
@@ -167,29 +198,46 @@ public class AutoActions{
|
|||||||
|
|
||||||
if (motif_id == 21) {
|
if (motif_id == 21) {
|
||||||
if (mostGreenSlot == 1) {
|
if (mostGreenSlot == 1) {
|
||||||
spin1PosFirst();
|
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||||
|
shootForward = true;
|
||||||
|
spinEndPos = 0.95;
|
||||||
} else if (mostGreenSlot == 2) {
|
} else if (mostGreenSlot == 2) {
|
||||||
spin2PosFirst();
|
firstSpindexShootPos = spindexer_outtakeBall2;
|
||||||
|
shootForward = false;
|
||||||
|
spinEndPos = 0.05;
|
||||||
} else {
|
} else {
|
||||||
spin3PosFirst();
|
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||||
|
shootForward = true;
|
||||||
|
spinEndPos = 0.95;
|
||||||
}
|
}
|
||||||
} else if (motif_id == 22) {
|
} else if (motif_id == 22) {
|
||||||
if (mostGreenSlot == 1) {
|
if (mostGreenSlot == 1) {
|
||||||
spin2PosFirst();
|
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||||
|
shootForward = true;
|
||||||
|
spinEndPos = 0.95;
|
||||||
} else if (mostGreenSlot == 2) {
|
} else if (mostGreenSlot == 2) {
|
||||||
spin3PosFirst();
|
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||||
|
shootForward = true;
|
||||||
|
spinEndPos = 0.95;
|
||||||
} else {
|
} else {
|
||||||
reverseSpin2PosFirst();
|
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||||
|
shootForward = false;
|
||||||
|
spinEndPos = 0.03;
|
||||||
}
|
}
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
if (mostGreenSlot == 1) {
|
if (mostGreenSlot == 1) {
|
||||||
spin3PosFirst();
|
firstSpindexShootPos = spindexer_outtakeBall3;
|
||||||
|
shootForward = false;
|
||||||
|
spinEndPos = 0.05;
|
||||||
} else if (mostGreenSlot == 2) {
|
} else if (mostGreenSlot == 2) {
|
||||||
oddSpin3PosFirst();
|
firstSpindexShootPos = spindexer_outtakeBall3b;
|
||||||
|
shootForward = true;
|
||||||
|
spinEndPos = 0.95;
|
||||||
} else {
|
} else {
|
||||||
spin1PosFirst();
|
firstSpindexShootPos = spindexer_outtakeBall1;
|
||||||
}
|
shootForward = true;
|
||||||
|
spinEndPos = 0.95; }
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
@@ -207,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() {
|
return new Action() {
|
||||||
int ticker = 1;
|
int ticker = 1;
|
||||||
|
|
||||||
@@ -215,6 +263,7 @@ public class AutoActions{
|
|||||||
|
|
||||||
int shooterTicker = 0;
|
int shooterTicker = 0;
|
||||||
Action manageShooter = null;
|
Action manageShooter = null;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
drive.updatePoseEstimate();
|
drive.updatePoseEstimate();
|
||||||
@@ -228,7 +277,7 @@ public class AutoActions{
|
|||||||
|
|
||||||
if (ticker == 1) {
|
if (ticker == 1) {
|
||||||
stamp = System.currentTimeMillis();
|
stamp = System.currentTimeMillis();
|
||||||
manageShooter = manageShooterAuto(shootTime, 0.501, 0.501, 0.501);
|
manageShooter = manageShooterAuto(shootTime, posX, posY, posH, false);
|
||||||
|
|
||||||
}
|
}
|
||||||
ticker++;
|
ticker++;
|
||||||
@@ -239,15 +288,14 @@ public class AutoActions{
|
|||||||
|
|
||||||
boolean end;
|
boolean end;
|
||||||
if (shootForward) {
|
if (shootForward) {
|
||||||
end = prevSpinPos > spinEndPos;
|
end = servos.getSpinPos() > spinEndPos;
|
||||||
} else {
|
} else {
|
||||||
end = prevSpinPos < spinEndPos;
|
end = servos.getSpinPos() < spinEndPos;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (System.currentTimeMillis() - stamp < shootTime * 1000 && (!end || shooterTicker < Spindexer.waitFirstBallTicks + 1)) {
|
if (System.currentTimeMillis() - stamp < shootTime * 1000 && (!end || shooterTicker < Spindexer.waitFirstBallTicks + 1)) {
|
||||||
|
|
||||||
if (!servos.spinEqual(firstSpindexShootPos) && shooterTicker < 1) {
|
if (!servos.spinEqual(firstSpindexShootPos) && shooterTicker < 1) {
|
||||||
servos.setTransferPos(transferServo_out);
|
|
||||||
servos.setSpinPos(firstSpindexShootPos);
|
servos.setSpinPos(firstSpindexShootPos);
|
||||||
} else {
|
} else {
|
||||||
servos.setTransferPos(transferServo_in);
|
servos.setTransferPos(transferServo_in);
|
||||||
@@ -276,6 +324,77 @@ public class AutoActions{
|
|||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
|
public Action shootAllManual(
|
||||||
|
double shootTime,
|
||||||
|
double hoodMoveTime, //Set to 0.501 to show that you are not using, but you must set hoodPoses equal
|
||||||
|
double spindexSpeed,
|
||||||
|
double velStart,
|
||||||
|
double hoodStart,
|
||||||
|
double velEnd,
|
||||||
|
double hoodEnd,
|
||||||
|
double turr) {
|
||||||
|
return new Action() {
|
||||||
|
int ticker = 1;
|
||||||
|
|
||||||
|
double stamp = 0.0;
|
||||||
|
|
||||||
|
int shooterTicker = 0;
|
||||||
|
Action manageShooter = null;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
|
teleStart = drive.localizer.getPose();
|
||||||
|
|
||||||
|
spindexer.setIntakePower(-0.1);
|
||||||
|
|
||||||
|
light.setState(StateEnums.LightState.BALL_COLOR);
|
||||||
|
light.update();
|
||||||
|
|
||||||
|
if (ticker == 1) {
|
||||||
|
stamp = System.currentTimeMillis();
|
||||||
|
manageShooter = manageShooterManual(shootTime, hoodMoveTime, velStart, hoodStart, velEnd, hoodEnd, turr);
|
||||||
|
|
||||||
|
}
|
||||||
|
ticker++;
|
||||||
|
|
||||||
|
manageShooter.run(telemetryPacket);
|
||||||
|
|
||||||
|
double prevSpinPos = servos.getSpinCmdPos();
|
||||||
|
|
||||||
|
boolean end;
|
||||||
|
if (shootForward) {
|
||||||
|
end = prevSpinPos > spinEndPos;
|
||||||
|
} else {
|
||||||
|
end = prevSpinPos < spinEndPos;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (System.currentTimeMillis() - stamp < shootTime * 1000 && !end) {
|
||||||
|
servos.setTransferPos(transferServo_in);
|
||||||
|
shooterTicker++;
|
||||||
|
Spindexer.whileShooting = true;
|
||||||
|
if (shootForward && shooterTicker > Spindexer.waitFirstBallTicks) {
|
||||||
|
servos.setSpinPos(prevSpinPos + spindexSpeed);
|
||||||
|
} else if (shooterTicker > Spindexer.waitFirstBallTicks) {
|
||||||
|
servos.setSpinPos(prevSpinPos - spindexSpeed);
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
|
||||||
|
} else {
|
||||||
|
servos.setTransferPos(transferServo_out);
|
||||||
|
Spindexer.whileShooting = false;
|
||||||
|
spindexer.resetSpindexer();
|
||||||
|
spindexer.processIntake();
|
||||||
|
|
||||||
|
return false;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
public Action intake(
|
public Action intake(
|
||||||
double time,
|
double time,
|
||||||
double posX,
|
double posX,
|
||||||
@@ -286,11 +405,12 @@ public class AutoActions{
|
|||||||
double stamp = 0.0;
|
double stamp = 0.0;
|
||||||
int ticker = 0;
|
int ticker = 0;
|
||||||
Action manageShooter = null;
|
Action manageShooter = null;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
if (ticker == 0) {
|
if (ticker == 0) {
|
||||||
stamp = System.currentTimeMillis();
|
stamp = System.currentTimeMillis();
|
||||||
manageShooter = manageShooterAuto(time, posX, posY, posH);
|
manageShooter = manageShooterAuto(time, posX, posY, posH, false);
|
||||||
}
|
}
|
||||||
ticker++;
|
ticker++;
|
||||||
|
|
||||||
@@ -305,12 +425,18 @@ public class AutoActions{
|
|||||||
|
|
||||||
manageShooter.run(telemetryPacket);
|
manageShooter.run(telemetryPacket);
|
||||||
|
|
||||||
return ((System.currentTimeMillis() - stamp) < (time * 1000)) && !spindexer.isFull();
|
if ((System.currentTimeMillis() - stamp) > (time * 1000)) {
|
||||||
|
servos.setSpinPos(spindexer_intakePos1);
|
||||||
|
return false;
|
||||||
|
} else {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
private boolean detectingObelisk = false;
|
private boolean detectingObelisk = false;
|
||||||
|
|
||||||
public Action detectObelisk(
|
public Action detectObelisk(
|
||||||
double time,
|
double time,
|
||||||
double posX,
|
double posX,
|
||||||
@@ -328,6 +454,7 @@ public class AutoActions{
|
|||||||
|
|
||||||
double stamp = 0.0;
|
double stamp = 0.0;
|
||||||
int ticker = 0;
|
int ticker = 0;
|
||||||
|
int prevMotif = 0;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
@@ -338,18 +465,23 @@ public class AutoActions{
|
|||||||
if (ticker == 0) {
|
if (ticker == 0) {
|
||||||
stamp = System.currentTimeMillis();
|
stamp = System.currentTimeMillis();
|
||||||
turret.pipelineSwitch(1);
|
turret.pipelineSwitch(1);
|
||||||
|
ticker++;
|
||||||
}
|
}
|
||||||
|
|
||||||
ticker++;
|
|
||||||
motif = turret.detectObelisk();
|
motif = turret.detectObelisk();
|
||||||
|
|
||||||
|
if (prevMotif == motif){
|
||||||
|
ticker++;
|
||||||
|
}
|
||||||
|
prevMotif = motif;
|
||||||
|
|
||||||
turret.setTurret(turrPos);
|
turret.setTurret(turrPos);
|
||||||
|
|
||||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
||||||
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
|
||||||
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
|
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;
|
teleStart = currentPose;
|
||||||
|
|
||||||
@@ -373,7 +505,8 @@ public class AutoActions{
|
|||||||
double time,
|
double time,
|
||||||
double posX,
|
double posX,
|
||||||
double posY,
|
double posY,
|
||||||
double posH
|
double posH,
|
||||||
|
boolean flywheelSensor
|
||||||
) {
|
) {
|
||||||
|
|
||||||
return new Action() {
|
return new Action() {
|
||||||
@@ -383,6 +516,112 @@ public class AutoActions{
|
|||||||
|
|
||||||
final boolean timeFallback = (time != 0.501);
|
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++;
|
||||||
|
|
||||||
|
double robotX = currentPose.position.x;
|
||||||
|
double robotY = currentPose.position.y;
|
||||||
|
|
||||||
|
double robotHeading = currentPose.heading.toDouble();
|
||||||
|
|
||||||
|
double goalX = -15;
|
||||||
|
double goalY = 0;
|
||||||
|
|
||||||
|
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));
|
||||||
|
} else {
|
||||||
|
deltaPose = new Pose2d(dx, dy, robotHeading);
|
||||||
|
}
|
||||||
|
Turret.limelightUsed = true;
|
||||||
|
|
||||||
|
// double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||||
|
|
||||||
|
targetingSettings = targeting.calculateSettings
|
||||||
|
(robotX, robotY, robotHeading, 0.0, false);
|
||||||
|
|
||||||
|
if (!detectingObelisk) {
|
||||||
|
turret.trackGoal(deltaPose);
|
||||||
|
}
|
||||||
|
|
||||||
|
servos.setHoodPos(targetingSettings.hoodAngle);
|
||||||
|
|
||||||
|
double voltage = robot.voltage.getVoltage();
|
||||||
|
flywheel.setPIDF(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F / voltage);
|
||||||
|
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
|
||||||
|
|
||||||
|
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
||||||
|
boolean shouldFinish = timeDone || (flywheel.getSteady() && flywheelSensor);
|
||||||
|
|
||||||
|
teleStart = currentPose;
|
||||||
|
|
||||||
|
TELE.addData("Steady?", flywheel.getSteady());
|
||||||
|
TELE.update();
|
||||||
|
|
||||||
|
return !shouldFinish;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action Wait(double time) {
|
||||||
|
return new Action() {
|
||||||
|
boolean ticker = false;
|
||||||
|
double stamp = 0.0;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
if (!ticker) {
|
||||||
|
stamp = System.currentTimeMillis();
|
||||||
|
ticker = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return (System.currentTimeMillis() - stamp < time * 1000);
|
||||||
|
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
public Action manageShooterManual(
|
||||||
|
double maxTime,
|
||||||
|
double hoodMoveTime, //Set to 0.501 to show that you are not using, but you must set hoodPoses equal
|
||||||
|
double velStart,
|
||||||
|
double hoodStart,
|
||||||
|
double velEnd,
|
||||||
|
double hoodEnd,
|
||||||
|
double turr
|
||||||
|
) {
|
||||||
|
return new Action() {
|
||||||
|
|
||||||
|
double stamp = 0.0;
|
||||||
|
int ticker = 0;
|
||||||
|
|
||||||
|
final boolean timeFallback = (maxTime != 0.501);
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
|
|
||||||
@@ -406,36 +645,30 @@ public class AutoActions{
|
|||||||
double dx = robotX - goalX; // delta x from robot to goal
|
double dx = robotX - goalX; // delta x from robot to goal
|
||||||
double dy = robotY - goalY; // delta y from robot to goal
|
double dy = robotY - goalY; // delta y from robot to goal
|
||||||
Pose2d deltaPose;
|
Pose2d deltaPose;
|
||||||
if (posX != 0.501) {
|
if (turr == 0.501) {
|
||||||
deltaPose = new Pose2d(posX, posY, Math.toRadians(posH));
|
deltaPose = new Pose2d(dx, dy, robotHeading);
|
||||||
} else {
|
|
||||||
deltaPose = new Pose2d(robotX, robotY, robotHeading);
|
|
||||||
}
|
|
||||||
|
|
||||||
// double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
|
||||||
|
|
||||||
targetingSettings = targeting.calculateSettings
|
|
||||||
(robotX, robotY, robotHeading, 0.0, false);
|
|
||||||
|
|
||||||
if (!detectingObelisk) {
|
if (!detectingObelisk) {
|
||||||
turret.trackGoal(deltaPose);
|
turret.trackGoal(deltaPose);
|
||||||
}
|
}
|
||||||
|
} else {
|
||||||
|
turret.setTurret(turr);
|
||||||
|
}
|
||||||
|
|
||||||
servos.setHoodPos(targetingSettings.hoodAngle);
|
servos.setHoodPos(hoodStart + ((hoodEnd - hoodStart) * Math.min(((System.currentTimeMillis() - stamp) / (hoodMoveTime * 1000)), 1)));
|
||||||
|
double vel = velStart + (velEnd - velStart) * Math.min(((System.currentTimeMillis() - stamp) / (hoodMoveTime * 1000)), 1);
|
||||||
|
|
||||||
double voltage = robot.voltage.getVoltage();
|
double voltage = robot.voltage.getVoltage();
|
||||||
flywheel.setPIDF(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F / voltage);
|
flywheel.setPIDF(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F / voltage);
|
||||||
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
|
flywheel.manageFlywheel(vel);
|
||||||
|
|
||||||
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
|
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > maxTime * 1000;
|
||||||
boolean shouldFinish = timeDone || flywheel.getSteady();
|
|
||||||
|
|
||||||
teleStart = currentPose;
|
teleStart = currentPose;
|
||||||
|
|
||||||
TELE.addData("Steady?", flywheel.getSteady());
|
TELE.addData("Steady?", flywheel.getSteady());
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
return !shouldFinish;
|
return !timeDone;
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -10,14 +10,18 @@ public class Back_Poses {
|
|||||||
public static double rShootX = 100, rShootY = 55, rShootH = 90;
|
public static double rShootX = 100, rShootY = 55, rShootH = 90;
|
||||||
public static double bShootX = 100, bShootY = -55, bShootH = -90;
|
public static double bShootX = 100, bShootY = -55, bShootH = -90;
|
||||||
|
|
||||||
public static double rStackPickupAX = 75, rStackPickupAY = 53, rStackPickupAH = 140;
|
public static double rStackPickupAX = 73, rStackPickupAY = 51, rStackPickupAH = 140;
|
||||||
public static double bStackPickupAX = 75, bStackPickupAY = -53, bStackPickupAH = -140;
|
public static double bStackPickupAX = 75, bStackPickupAY = -53, bStackPickupAH = -140;
|
||||||
|
|
||||||
public static double rStackPickupBX = 55, rStackPickupBY = 73, rStackPickupBH = 140.1;
|
public static double rStackPickupBX = 53, rStackPickupBY = 71, rStackPickupBH = 140.1;
|
||||||
public static double bStackPickupBX = 50, bStackPickupBY = -78, bStackPickupBH = -140.1;
|
public static double bStackPickupBX = 55, bStackPickupBY = -73, bStackPickupBH = -140.1;
|
||||||
|
|
||||||
|
public static double rPickupGateX = 50, rPickupGateY = 83, rPickupGateH = 140;
|
||||||
|
public static double bPickupGateX = 70, bPickupGateY = -90, bPickupGateH = -140;
|
||||||
|
public static double pickupGateXB = 84, pickupGateYB = 76, pickupGateHB = 140;
|
||||||
|
public static double pickupGateXC = 50, pickupGateYC = 83, pickupGateHC = 190;
|
||||||
|
|
||||||
|
|
||||||
public static double rPickupGateX = 70, rPickupGateY = 90, rPickupGateH = 140;
|
|
||||||
public static double bPickupGateX = 60, bPickupGateY = -88, bPickupGateH = -140;
|
|
||||||
|
|
||||||
public static double autoStartRX = 103, autoStartRY = 63.5, autoStartRH = 50;
|
public static double autoStartRX = 103, autoStartRY = 63.5, autoStartRH = 50;
|
||||||
public static double autoStartBX = 103, autoStartBY = -63.5, autoStartBH = -50;
|
public static double autoStartBX = 103, autoStartBY = -63.5, autoStartBH = -50;
|
||||||
|
|||||||
@@ -8,33 +8,33 @@ public class Front_Poses {
|
|||||||
|
|
||||||
|
|
||||||
public static double rx1 = 20, ry1 = 0.5, rh1 = 0.1;
|
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 bx1 = 20, by1 = -0.5, bh1 = -0.1;
|
||||||
|
|
||||||
public static double rx2a = 41, ry2a = 18, rh2a = 140;
|
public static double rx2a = 41, ry2a = 18, rh2a = 140;
|
||||||
public static double bx2a = 41, by2a = -18, bh2a = -140;
|
public static double bx2a = 41, by2a = -18, bh2a = -140;
|
||||||
|
|
||||||
public static double rx2b = 23, ry2b = 36, rh2b = 140.1;
|
public static double rx2b = 21, ry2b = 34, rh2b = 140.1;
|
||||||
public static double bx2b = 19, by2b = -40, bh2b = -140.1;
|
public static double bx2b = 23, by2b = -36, bh2b = -140.1;
|
||||||
|
|
||||||
public static double rx3a = 55, ry3a = 39, rh3a = 140;
|
public static double rx3a = 55, ry3a = 39, rh3a = 140;
|
||||||
public static double bx3a = 55, by3a = -39, bh3a = -140;
|
public static double bx3a = 55, by3a = -39, bh3a = -140;
|
||||||
|
|
||||||
public static double rx3aG = 60, ry3aG = 34, rh3aG = 140;
|
public static double rx3aG = 60, ry3aG = 34, rh3aG = 140;
|
||||||
public static double bx3aG = 55, by3aG = -43, bh3aG = -140;
|
public static double bx3aG = 60, by3aG = -34, bh3aG = -140;
|
||||||
|
|
||||||
public static double rx3b = 36, ry3b = 58, rh3b = 140.1;
|
public static double rx3b = 36, ry3b = 58, rh3b = 140.1;
|
||||||
public static double bx3b = 41, by3b = -59, bh3b = -140.1;
|
public static double bx3b = 36, by3b = -58, bh3b = -140.1;
|
||||||
|
|
||||||
public static double rx4a = 75, ry4a = 53, rh4a = 140;
|
public static double rx4a = 75, ry4a = 53, rh4a = 140;
|
||||||
public static double bx4a = 75, by4a = -53, bh4a = -140;
|
public static double bx4a = 75, by4a = -53, bh4a = -140;
|
||||||
|
|
||||||
public static double rx4b = 50, ry4b = 78, rh4b = 140.1;
|
public static double rx4b = 50, ry4b = 78, rh4b = 140.1;
|
||||||
public static double bx4b = 47, by4b = -85, bh4b = -140.1;
|
public static double bx4b = 50, by4b = -78, bh4b = -140.1;
|
||||||
|
|
||||||
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0;
|
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0;
|
||||||
|
|
||||||
public static double rShootX = 40, rShootY = 10, rShootH = 50;
|
public static double rShootX = 40, rShootY = 10, rShootH = 50;
|
||||||
public static double bShootX = 40, bShootY = 0, bShootH = -50;
|
public static double bShootX = 40, bShootY = -10, bShootH = -50;
|
||||||
|
|
||||||
public static double rxPrep = 45, ryPrep = 10, rhPrep = 50;
|
public static double rxPrep = 45, ryPrep = 10, rhPrep = 50;
|
||||||
public static double bxPrep = 45, byPrep = -10, bhPrep = -50;
|
public static double bxPrep = 45, byPrep = -10, bhPrep = -50;
|
||||||
@@ -42,5 +42,21 @@ public class Front_Poses {
|
|||||||
public static double rLeaveX = 40, rLeaveY = -7, rLeaveH = 55;
|
public static double rLeaveX = 40, rLeaveY = -7, rLeaveH = 55;
|
||||||
public static double bLeaveX = 40, bLeaveY = 7, bLeaveH = -55;
|
public static double bLeaveX = 40, bLeaveY = 7, bLeaveH = -55;
|
||||||
|
|
||||||
|
public static double rShoot0X = 53, rShoot0Y = 10.1, rShoot0H = 80.1;
|
||||||
|
public static double bShoot0X = 53, bShoot0Y = -10.1, bShoot0H = -80.1;
|
||||||
|
|
||||||
|
public static double rShootGateX = 50, rShootGateY = 10, rShootGateH = 90;
|
||||||
|
public static double bShootGateX = 50, bShootGateY = -10, bShootGateH = -90;
|
||||||
|
|
||||||
|
public static double rLeaveGateX = 40, rLeaveGateY = -7, rLeaveGateH = 55;
|
||||||
|
public static double bLeaveGateX = 40, bLeaveGateY = 7, bLeaveGateH = -55;
|
||||||
|
|
||||||
|
public static double rPickupGateAX = 31, rPickupGateAY = 53, rPickupGateAH = 150;
|
||||||
|
public static double bPickupGateAX = 24, bPickupGateAY = -50, bPickupGateAH = -150;
|
||||||
|
|
||||||
|
public static double rPickupGateBX = 38, rPickupGateBY = 62, rPickupGateBH = 210;
|
||||||
|
public static double bPickupGateBX = 38, bPickupGateBY = -68, bPickupGateBH = -180;
|
||||||
|
public static double pickupGateCX = 34, pickupGateCY = 58, pickupGateCH = 220;
|
||||||
|
|
||||||
public static Pose2d teleStart = new Pose2d(0, 0, 0);
|
public static Pose2d teleStart = new Pose2d(0, 0, 0);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -5,19 +5,19 @@ import com.acmerobotics.dashboard.config.Config;
|
|||||||
@Config
|
@Config
|
||||||
public class ServoPositions {
|
public class ServoPositions {
|
||||||
|
|
||||||
public static double spindexer_intakePos1 = 0.06; //0.13;
|
public static double spindexer_intakePos1 = 0.18; //0.13;
|
||||||
|
|
||||||
public static double spindexer_intakePos2 = 0.25; //0.33;//0.5;
|
public static double spindexer_intakePos2 = 0.37; //0.33;//0.5;
|
||||||
|
|
||||||
public static double spindexer_intakePos3 = 0.43; //0.53;//0.66;
|
public static double spindexer_intakePos3 = 0.56; //0.53;//0.66;
|
||||||
|
|
||||||
public static double spindexer_outtakeBall3 = 0.71; //0.65; //0.24;
|
public static double spindexer_outtakeBall3 = 0.84; //0.65; //0.24;
|
||||||
public static double spindexer_outtakeBall3b = 0.15; //0.65; //0.24;
|
public static double spindexer_outtakeBall3b = 0.27; //0.65; //0.24;
|
||||||
|
|
||||||
public static double spindexer_outtakeBall2 = 0.53; //0.46; //0.6;
|
public static double spindexer_outtakeBall2 = 0.66; //0.46; //0.6;
|
||||||
public static double spindexer_outtakeBall1 = 0.35; //0.27; //0.4;
|
public static double spindexer_outtakeBall1 = 0.47; //0.27; //0.4;
|
||||||
public static double spinStartPos = 0.3;
|
public static double spinStartPos = 0.10;
|
||||||
public static double spinEndPos = 0.85;
|
public static double spinEndPos = 0.95;
|
||||||
|
|
||||||
public static double shootAllSpindexerSpeedIncrease = 0.014;
|
public static double shootAllSpindexerSpeedIncrease = 0.014;
|
||||||
|
|
||||||
@@ -27,18 +27,20 @@ public class ServoPositions {
|
|||||||
|
|
||||||
public static double hoodAuto = 0.27;
|
public static double hoodAuto = 0.27;
|
||||||
|
|
||||||
public static double hoodOffset = -0.05;
|
public static double hoodOffset = -0.04; // offset from 0.93
|
||||||
|
|
||||||
public static double turret_redClose = 0;
|
public static double turret_redClose = 0;
|
||||||
public static double turret_blueClose = 0;
|
public static double turret_blueClose = 0;
|
||||||
|
|
||||||
// These values are ADDED to turrDefault
|
// These values are ADDED to turrDefault
|
||||||
public static double redObeliskTurrPos1 = 0.12;
|
public static double redObeliskTurrPos0 = -0.35;
|
||||||
public static double redObeliskTurrPos2 = 0.13;
|
public static double redObeliskTurrPos1 = 0.15;
|
||||||
public static double redObeliskTurrPos3 = 0.14;
|
public static double redObeliskTurrPos2 = 0.16;
|
||||||
public static double blueObeliskTurrPos1 = -0.12;
|
public static double redObeliskTurrPos3 = 0.17;
|
||||||
public static double blueObeliskTurrPos2 = -0.13;
|
public static double blueObeliskTurrPos0 = 0.35;
|
||||||
public static double blueObeliskTurrPos3 = -0.14;
|
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 redTurretShootPos = 0.05;
|
||||||
public static double blueTurretShootPos = -0.05;
|
public static double blueTurretShootPos = -0.05;
|
||||||
|
|
||||||
|
|||||||
@@ -201,18 +201,18 @@ public final class MecanumDrive {
|
|||||||
public double kA = 0.00008;
|
public double kA = 0.00008;
|
||||||
|
|
||||||
// path profile parameters (in inches)
|
// path profile parameters (in inches)
|
||||||
public double maxWheelVel = 90;
|
public double maxWheelVel = 70;
|
||||||
public double minProfileAccel = -40;
|
public double minProfileAccel = -40;
|
||||||
public double maxProfileAccel = 90;
|
public double maxProfileAccel = 70;
|
||||||
|
|
||||||
// turn profile parameters (in radians)
|
// turn profile parameters (in radians)
|
||||||
public double maxAngVel = Math.PI; // shared with path
|
public double maxAngVel = 2 *Math.PI; // shared with path
|
||||||
public double maxAngAccel = Math.PI;
|
public double maxAngAccel = 2 * Math.PI;
|
||||||
|
|
||||||
// path controller gains
|
// path controller gains
|
||||||
public double axialGain = 4;
|
public double axialGain = 6.0;
|
||||||
public double lateralGain = 4;
|
public double lateralGain = 6.0;
|
||||||
public double headingGain = 4; // shared with turn
|
public double headingGain = 6.0; // shared with turn
|
||||||
|
|
||||||
public double axialVelGain = 0.0;
|
public double axialVelGain = 0.0;
|
||||||
public double lateralVelGain = 0.0;
|
public double lateralVelGain = 0.0;
|
||||||
@@ -345,7 +345,16 @@ public final class MecanumDrive {
|
|||||||
t = Actions.now() - beginTs;
|
t = Actions.now() - beginTs;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (t >= timeTrajectory.duration) {
|
Pose2dDual<Time> txWorldTarget = timeTrajectory.get(t);
|
||||||
|
targetPoseWriter.write(new PoseMessage(txWorldTarget.value()));
|
||||||
|
|
||||||
|
PoseVelocity2d robotVelRobot = updatePoseEstimate();
|
||||||
|
|
||||||
|
Pose2d error = txWorldTarget.value().minusExp(localizer.getPose());
|
||||||
|
|
||||||
|
if ((t >= timeTrajectory.duration && error.position.norm() < 1
|
||||||
|
&& robotVelRobot.linearVel.norm() < 0.5)
|
||||||
|
|| t >= timeTrajectory.duration + 0.01) {
|
||||||
leftFront.setPower(0);
|
leftFront.setPower(0);
|
||||||
leftBack.setPower(0);
|
leftBack.setPower(0);
|
||||||
rightBack.setPower(0);
|
rightBack.setPower(0);
|
||||||
@@ -354,10 +363,6 @@ public final class MecanumDrive {
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
Pose2dDual<Time> txWorldTarget = timeTrajectory.get(t);
|
|
||||||
targetPoseWriter.write(new PoseMessage(txWorldTarget.value()));
|
|
||||||
|
|
||||||
PoseVelocity2d robotVelRobot = updatePoseEstimate();
|
|
||||||
|
|
||||||
PoseVelocity2dDual<Time> command = new HolonomicController(
|
PoseVelocity2dDual<Time> command = new HolonomicController(
|
||||||
PARAMS.axialGain, PARAMS.lateralGain, PARAMS.headingGain,
|
PARAMS.axialGain, PARAMS.lateralGain, PARAMS.headingGain,
|
||||||
@@ -388,7 +393,6 @@ public final class MecanumDrive {
|
|||||||
p.put("y", localizer.getPose().position.y);
|
p.put("y", localizer.getPose().position.y);
|
||||||
p.put("heading (deg)", Math.toDegrees(localizer.getPose().heading.toDouble()));
|
p.put("heading (deg)", Math.toDegrees(localizer.getPose().heading.toDouble()));
|
||||||
|
|
||||||
Pose2d error = txWorldTarget.value().minusExp(localizer.getPose());
|
|
||||||
p.put("xError", error.position.x);
|
p.put("xError", error.position.x);
|
||||||
p.put("yError", error.position.y);
|
p.put("yError", error.position.y);
|
||||||
p.put("headingError (deg)", Math.toDegrees(error.heading.toDouble()));
|
p.put("headingError (deg)", Math.toDegrees(error.heading.toDouble()));
|
||||||
|
|||||||
@@ -49,6 +49,8 @@ public final class PinpointLocalizer implements Localizer {
|
|||||||
txWorldPinpoint = initialPose;
|
txWorldPinpoint = initialPose;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void setPose(Pose2d pose) {
|
public void setPose(Pose2d pose) {
|
||||||
txWorldPinpoint = pose.times(txPinpointRobot.inverse());
|
txWorldPinpoint = pose.times(txPinpointRobot.inverse());
|
||||||
|
|||||||
@@ -65,6 +65,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
boolean reject = false;
|
boolean reject = false;
|
||||||
double xOffset = 0.0;
|
double xOffset = 0.0;
|
||||||
double yOffset = 0.0;
|
double yOffset = 0.0;
|
||||||
|
double hOffset = 0.0;
|
||||||
// double headingOffset = 0.0;
|
// double headingOffset = 0.0;
|
||||||
int ticker = 0;
|
int ticker = 0;
|
||||||
|
|
||||||
@@ -75,6 +76,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
int intakeTicker = 0;
|
int intakeTicker = 0;
|
||||||
private boolean shootAll = false;
|
private boolean shootAll = false;
|
||||||
|
boolean relocalize = false;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
@@ -111,7 +113,6 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
light.setState(StateEnums.LightState.MANUAL);
|
light.setState(StateEnums.LightState.MANUAL);
|
||||||
limelightUsed = true;
|
limelightUsed = true;
|
||||||
|
|
||||||
robot.light.setPosition(1);
|
|
||||||
while (opModeInInit()) {
|
while (opModeInInit()) {
|
||||||
robot.limelight.start();
|
robot.limelight.start();
|
||||||
if (redAlliance) {
|
if (redAlliance) {
|
||||||
@@ -122,6 +123,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
light.setManualLightColor(Color.LightBlue);
|
light.setManualLightColor(Color.LightBlue);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
robot.light.setPosition(1);
|
||||||
|
|
||||||
light.update();
|
light.update();
|
||||||
}
|
}
|
||||||
@@ -140,12 +142,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
//DRIVETRAIN:
|
//DRIVETRAIN:
|
||||||
|
|
||||||
drivetrain.drive(
|
drivetrain.drive(-gamepad1.right_stick_y, gamepad1.right_stick_x, gamepad1.left_stick_x, gamepad1.left_trigger);
|
||||||
-gamepad1.right_stick_y,
|
|
||||||
gamepad1.right_stick_x,
|
|
||||||
gamepad1.left_stick_x,
|
|
||||||
gamepad1.left_trigger
|
|
||||||
);
|
|
||||||
|
|
||||||
if (gamepad1.right_bumper) {
|
if (gamepad1.right_bumper) {
|
||||||
|
|
||||||
@@ -165,10 +162,11 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
double robX = drive.localizer.getPose().position.x;
|
double robX = drive.localizer.getPose().position.x;
|
||||||
double robY = drive.localizer.getPose().position.y;
|
double robY = drive.localizer.getPose().position.y;
|
||||||
|
double robH = drive.localizer.getPose().heading.toDouble();
|
||||||
|
|
||||||
double robotX = robX - xOffset;
|
double robotX = robX + xOffset;
|
||||||
double robotY = robY - yOffset;
|
double robotY = robY + yOffset;
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
double robotHeading = robH + hOffset;
|
||||||
|
|
||||||
double goalX = -15;
|
double goalX = -15;
|
||||||
double goalY = 0;
|
double goalY = 0;
|
||||||
@@ -179,10 +177,23 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
// double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
// double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||||
|
|
||||||
targetingSettings = targeting.calculateSettings
|
targetingSettings = targeting.calculateSettings(robotX, robotY, robotHeading, 0.0, turretInterpolate);
|
||||||
(robotX, robotY, robotHeading, 0.0, turretInterpolate);
|
|
||||||
|
|
||||||
|
//RELOCALIZATION
|
||||||
|
|
||||||
|
if (gamepad2.squareWasPressed()) {
|
||||||
|
relocalize = !relocalize;
|
||||||
|
gamepad2.rumble(500);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (relocalize) {
|
||||||
|
turret.relocalize();
|
||||||
|
xOffset = -((turret.getLimelightZ() * 39.3701) + Turret.limelightPosOffset) - robX;
|
||||||
|
yOffset = (turret.getLimelightX() * 39.3701) - robY;
|
||||||
|
hOffset = (Math.toRadians(turret.getLimelightH())) - robH;
|
||||||
|
} else {
|
||||||
turret.trackGoal(deltaPose);
|
turret.trackGoal(deltaPose);
|
||||||
|
}
|
||||||
|
|
||||||
//VELOCITY AUTOMATIC
|
//VELOCITY AUTOMATIC
|
||||||
if (autoVel) {
|
if (autoVel) {
|
||||||
@@ -214,6 +225,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
//HOOD:
|
//HOOD:
|
||||||
|
|
||||||
|
|
||||||
if (targetingHood) {
|
if (targetingHood) {
|
||||||
servo.setHoodPos(targetingSettings.hoodAngle + autoHoodOffset);
|
servo.setHoodPos(targetingSettings.hoodAngle + autoHoodOffset);
|
||||||
} else {
|
} else {
|
||||||
@@ -250,7 +262,6 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
if (enableSpindexerManager) {
|
if (enableSpindexerManager) {
|
||||||
//if (!shootAll) {
|
//if (!shootAll) {
|
||||||
spindexer.processIntake();
|
spindexer.processIntake();
|
||||||
@@ -282,7 +293,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
if (shooterTicker == 0) {
|
if (shooterTicker == 0) {
|
||||||
spindexer.prepareShootAllContinous();
|
spindexer.prepareShootAllContinous();
|
||||||
//TELE.addLine("preparing to shoot");
|
//TELE.addLine("preparing to shoot");
|
||||||
// } else if (shooterTicker == 2) {
|
// else if (shooterTicker == 2) {
|
||||||
// //servo.setTransferPos(transferServo_in);
|
// //servo.setTransferPos(transferServo_in);
|
||||||
// spindexer.shootAll();
|
// spindexer.shootAll();
|
||||||
// TELE.addLine("starting to shoot");
|
// TELE.addLine("starting to shoot");
|
||||||
@@ -339,18 +350,22 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
// Targeting Debug
|
// Targeting Debug
|
||||||
TELE.addData("robotX", robotX);
|
TELE.addData("robotX", robotX);
|
||||||
TELE.addData("robotY", robotY);
|
TELE.addData("robotY", robotY);
|
||||||
TELE.addData("robotInchesX", targeting.robotInchesX);
|
TELE.addData("robot H", robotHeading);
|
||||||
TELE.addData("robotInchesY", targeting.robotInchesY);
|
// TELE.addData("robotInchesX", targeting.robotInchesX);
|
||||||
TELE.addData("Targeting Interpolate", turretInterpolate);
|
// TELE.addData("robotInchesY", targeting.robotInchesY);
|
||||||
|
// TELE.addData("Targeting Interpolate", turretInterpolate);
|
||||||
TELE.addData("Targeting GridX", targeting.robotGridX);
|
TELE.addData("Targeting GridX", targeting.robotGridX);
|
||||||
TELE.addData("Targeting GridY", targeting.robotGridY);
|
TELE.addData("Targeting GridY", targeting.robotGridY);
|
||||||
TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM);
|
// TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM);
|
||||||
TELE.addData("Targeting HoodAngle", targetingSettings.hoodAngle);
|
// TELE.addData("Targeting HoodAngle", targetingSettings.hoodAngle);
|
||||||
TELE.addData("timeSinceStamp", getRuntime() - shootStamp);
|
// TELE.addData("timeSinceStamp", getRuntime() - shootStamp);
|
||||||
TELE.addData("Voltage", voltage); // returns alleged recorded voltage (not same as driver hub)
|
// TELE.addData("Voltage", voltage); // returns alleged recorded voltage (not same as driver hub)
|
||||||
TELE.addData("Avg Loop Time", loopTimes.getAvgLoopTime());
|
TELE.addData("Avg Loop Time", loopTimes.getAvgLoopTime());
|
||||||
TELE.addData("Min Loop Time", loopTimes.getMinLoopTimeOneMin());
|
TELE.addData("Min Loop Time", loopTimes.getMinLoopTimeOneMin());
|
||||||
TELE.addData("Max Loop Time", loopTimes.getMaxLoopTimeOneMin());
|
TELE.addData("Max Loop Time", loopTimes.getMaxLoopTimeOneMin());
|
||||||
|
TELE.addData("Tag Pos X", -((turret.getLimelightZ() * 39.3701) + Turret.limelightPosOffset));
|
||||||
|
TELE.addData("Tag Pos Y", turret.getLimelightX() * 39.3701);
|
||||||
|
TELE.addData("Tag Pos H", Math.toRadians(turret.getLimelightH()));
|
||||||
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
|
|||||||
@@ -7,6 +7,7 @@ import com.acmerobotics.dashboard.config.Config;
|
|||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
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.robotcore.external.navigation.DistanceUnit;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
@@ -28,16 +29,20 @@ public class ColorTest extends LinearOpMode {
|
|||||||
if (isStopRequested()) return;
|
if (isStopRequested()) return;
|
||||||
|
|
||||||
while(opModeIsActive()){
|
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);
|
double dist1 = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
color1Distance = (colorFilterAlpha * dist1) + ((1-colorFilterAlpha) * color1Distance);
|
color1Distance = (colorFilterAlpha * dist1) + ((1-colorFilterAlpha) * color1Distance);
|
||||||
|
|
||||||
TELE.addData("Color1 toColor", robot.color1.getNormalizedColors().toColor());
|
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);
|
TELE.addData("Color1 distance (mm)", color1Distance);
|
||||||
|
|
||||||
|
|
||||||
// ----- COLOR 2 -----
|
// ----- COLOR 2 -----
|
||||||
double green2 = robot.color2.getNormalizedColors().green;
|
double green2 = robot.color2.getNormalizedColors().green;
|
||||||
double blue2 = robot.color2.getNormalizedColors().blue;
|
double blue2 = robot.color2.getNormalizedColors().blue;
|
||||||
|
|||||||
@@ -2,6 +2,7 @@ package org.firstinspires.ftc.teamcode.tests;
|
|||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
|
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStart;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.hoodOffset;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
|
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_intakePos1;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||||
@@ -128,9 +129,9 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
|
|
||||||
if (hoodPos != 0.501) {
|
if (hoodPos != 0.501) {
|
||||||
if (enableHoodAutoOpen) {
|
if (enableHoodAutoOpen) {
|
||||||
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)));
|
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)) + hoodOffset);
|
||||||
} else {
|
} else {
|
||||||
robot.hood.setPosition(hoodPos);
|
robot.hood.setPosition(hoodPos + hoodOffset);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -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();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -187,7 +187,7 @@ public class Spindexer {
|
|||||||
distanceFrontPassenger = (colorFilterAlpha * dFrontPassenger) + ((1-colorFilterAlpha) * distanceFrontPassenger);
|
distanceFrontPassenger = (colorFilterAlpha * dFrontPassenger) + ((1-colorFilterAlpha) * distanceFrontPassenger);
|
||||||
|
|
||||||
// Position 1
|
// Position 1
|
||||||
if (distanceRearCenter < 60) {
|
if (distanceRearCenter < 48) {
|
||||||
|
|
||||||
// Mark Ball Found
|
// Mark Ball Found
|
||||||
newPos1Detection = true;
|
newPos1Detection = true;
|
||||||
@@ -209,7 +209,7 @@ public class Spindexer {
|
|||||||
// Position 2
|
// Position 2
|
||||||
// Find which ball position this is in the spindexer
|
// Find which ball position this is in the spindexer
|
||||||
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()];
|
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()];
|
||||||
if (distanceFrontDriver < 56) {
|
if (distanceFrontDriver < 50) {
|
||||||
// reset FoundEmpty because looking for 3 in a row before reset
|
// reset FoundEmpty because looking for 3 in a row before reset
|
||||||
ballPositions[spindexerBallPos].foundEmpty = 0;
|
ballPositions[spindexerBallPos].foundEmpty = 0;
|
||||||
if (detectFrontColor) {
|
if (detectFrontColor) {
|
||||||
@@ -671,8 +671,10 @@ public class Spindexer {
|
|||||||
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.REARCENTER.ordinal()]].ballColor;
|
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.REARCENTER.ordinal()]].ballColor;
|
||||||
}
|
}
|
||||||
private double prevPow = 0.501;
|
private double prevPow = 0.501;
|
||||||
|
private boolean firstIntakePow = true;
|
||||||
public void setIntakePower(double pow){
|
public void setIntakePower(double pow){
|
||||||
if (prevPow != 0.501 && prevPow != pow){
|
if (firstIntakePow || prevPow != pow){
|
||||||
|
firstIntakePow = false;
|
||||||
robot.intake.setPower(pow);
|
robot.intake.setPower(pow);
|
||||||
}
|
}
|
||||||
prevPow = pow;
|
prevPow = pow;
|
||||||
|
|||||||
@@ -82,13 +82,19 @@ public class Targeting {
|
|||||||
public Targeting() {
|
public Targeting() {
|
||||||
}
|
}
|
||||||
|
|
||||||
|
double cos54 = Math.cos(Math.toRadians(-54));
|
||||||
|
double sin54 = Math.sin(Math.toRadians(-54));
|
||||||
|
|
||||||
public Settings calculateSettings(double robotX, double robotY, double robotHeading, double robotVelocity, boolean interpolate) {
|
public Settings calculateSettings(double robotX, double robotY, double robotHeading, double robotVelocity, boolean interpolate) {
|
||||||
Settings recommendedSettings = new Settings(0.0, 0.0);
|
Settings recommendedSettings = new Settings(0.0, 0.0);
|
||||||
|
if (!redAlliance){
|
||||||
double cos45 = Math.cos(Math.toRadians(-45));
|
sin54 = Math.sin(Math.toRadians(54));
|
||||||
double sin45 = Math.sin(Math.toRadians(-45));
|
} else {
|
||||||
double rotatedY = (robotX + cancelOffsetX) * sin45 + (robotY + cancelOffsetY) * cos45;
|
sin54 = Math.sin(Math.toRadians(-54));
|
||||||
double rotatedX = (robotX + cancelOffsetX) * cos45 - (robotY + cancelOffsetY) * sin45;
|
}
|
||||||
|
// TODO: test these values determined from the fmap
|
||||||
|
double rotatedY = (robotX + cancelOffsetX) * sin54 + (robotY + cancelOffsetY) * cos54;
|
||||||
|
double rotatedX = (robotX + cancelOffsetX) * cos54 - (robotY + cancelOffsetY) * sin54;
|
||||||
|
|
||||||
// Convert robot coordinates to inches
|
// Convert robot coordinates to inches
|
||||||
robotInchesX = rotatedX * unitConversionFactor;
|
robotInchesX = rotatedX * unitConversionFactor;
|
||||||
@@ -99,7 +105,17 @@ public class Targeting {
|
|||||||
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
|
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
|
||||||
|
|
||||||
int remX = Math.floorMod((int) robotInchesX, tileSize);
|
int remX = Math.floorMod((int) robotInchesX, tileSize);
|
||||||
int remY = Math.floorMod((int) robotInchesX, tileSize);
|
int remY = Math.floorMod((int) robotInchesY, tileSize);
|
||||||
|
|
||||||
|
//clamp
|
||||||
|
|
||||||
|
//if (redAlliance) {
|
||||||
|
robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
||||||
|
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
||||||
|
//} else {
|
||||||
|
// robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
||||||
|
// robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
||||||
|
//}
|
||||||
|
|
||||||
// Determine if we need to interpolate based on tile position.
|
// Determine if we need to interpolate based on tile position.
|
||||||
// if near upper or lower quarter or tile interpolate with next tile.
|
// if near upper or lower quarter or tile interpolate with next tile.
|
||||||
@@ -172,16 +188,6 @@ public class Targeting {
|
|||||||
interpolate = false;
|
interpolate = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
//clamp
|
|
||||||
|
|
||||||
if (redAlliance) {
|
|
||||||
robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
|
||||||
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
|
||||||
} else {
|
|
||||||
robotGridY = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
|
||||||
robotGridX = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
|
||||||
}
|
|
||||||
|
|
||||||
// basic search
|
// basic search
|
||||||
if (true) { //!interpolate) {
|
if (true) { //!interpolate) {
|
||||||
if ((robotGridY < 6) && (robotGridX < 6)) {
|
if ((robotGridY < 6) && (robotGridX < 6)) {
|
||||||
|
|||||||
@@ -14,6 +14,7 @@ import com.qualcomm.robotcore.hardware.DcMotor;
|
|||||||
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
|
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
|
||||||
import org.firstinspires.ftc.teamcode.constants.Color;
|
import org.firstinspires.ftc.teamcode.constants.Color;
|
||||||
|
|
||||||
|
import java.util.ArrayList;
|
||||||
import java.util.List;
|
import java.util.List;
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
@@ -22,12 +23,12 @@ public class Turret {
|
|||||||
|
|
||||||
public static double turretTolerance = 0.02;
|
public static double turretTolerance = 0.02;
|
||||||
public static double turrPosScalar = 0.00011264432;
|
public static double turrPosScalar = 0.00011264432;
|
||||||
public static double turret180Range = 0.4;
|
public static double turret180Range = 0.54;
|
||||||
public static double turrDefault = 0.37;
|
public static double turrDefault = 0.35;
|
||||||
public static double turrMin = 0.15;
|
public static double turrMin = 0;
|
||||||
public static double turrMax = 0.8;
|
public static double turrMax = 1;
|
||||||
public static boolean limelightUsed = true;
|
public static boolean limelightUsed = true;
|
||||||
|
public static double limelightPosOffset = 5;
|
||||||
public static double manualOffset = 0.0;
|
public static double manualOffset = 0.0;
|
||||||
|
|
||||||
// public static double visionCorrectionGain = 0.08; // Single tunable gain
|
// public static double visionCorrectionGain = 0.08; // Single tunable gain
|
||||||
@@ -58,6 +59,9 @@ public class Turret {
|
|||||||
private int prevPipeline = -1;
|
private int prevPipeline = -1;
|
||||||
PIDController bearingPID;
|
PIDController bearingPID;
|
||||||
|
|
||||||
|
public int llCoast = 0;
|
||||||
|
public int LL_COAST_TICKS = 60;
|
||||||
|
|
||||||
public Turret(Robot rob, MultipleTelemetry tele, Limelight3A cam) {
|
public Turret(Robot rob, MultipleTelemetry tele, Limelight3A cam) {
|
||||||
this.TELE = tele;
|
this.TELE = tele;
|
||||||
this.robot = rob;
|
this.robot = rob;
|
||||||
@@ -99,8 +103,12 @@ public class Turret {
|
|||||||
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
|
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
public static double alphaPosConstant = 0.3;
|
||||||
private void limelightRead() { // only for tracking purposes, not general reads
|
private void limelightRead() { // only for tracking purposes, not general reads
|
||||||
|
Double xPos = null;
|
||||||
|
Double yPos = null;
|
||||||
|
Double zPos = null;
|
||||||
|
Double hPos = null;
|
||||||
result = webcam.getLatestResult();
|
result = webcam.getLatestResult();
|
||||||
if (result != null) {
|
if (result != null) {
|
||||||
if (result.isValid()) {
|
if (result.isValid()) {
|
||||||
@@ -112,9 +120,27 @@ public class Turret {
|
|||||||
limelightPosX = botpose.getPosition().x;
|
limelightPosX = botpose.getPosition().x;
|
||||||
limelightPosY = botpose.getPosition().y;
|
limelightPosY = botpose.getPosition().y;
|
||||||
}
|
}
|
||||||
|
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||||
|
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||||
|
limelightTagPose = fiducial.getRobotPoseTargetSpace();
|
||||||
|
if (limelightTagPose != null){
|
||||||
|
xPos = limelightTagPose.getPosition().x;
|
||||||
|
yPos = limelightTagPose.getPosition().y;
|
||||||
|
zPos = limelightTagPose.getPosition().z;
|
||||||
|
hPos = limelightTagPose.getOrientation().getYaw();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
if (xPos != null){
|
||||||
|
if (zPos<0) {
|
||||||
|
limelightTagX = (alphaPosConstant * xPos) + ((1 - alphaPosConstant) * limelightTagX);
|
||||||
|
limelightTagY = (alphaPosConstant * yPos) + ((1 - alphaPosConstant) * limelightTagY);
|
||||||
|
limelightTagZ = (alphaPosConstant * zPos) + ((1 - alphaPosConstant) * limelightTagZ);
|
||||||
|
limelightTagH = (alphaPosConstant * hPos) + ((1 - alphaPosConstant) * limelightTagH);
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
public double getBearing() {
|
public double getBearing() {
|
||||||
@@ -127,12 +153,21 @@ public class Turret {
|
|||||||
return ty;
|
return ty;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Pose3D limelightTagPose;
|
||||||
|
double limelightTagX = 0.0;
|
||||||
|
double limelightTagY = 0.0;
|
||||||
|
double limelightTagZ = 0.0;
|
||||||
|
double limelightTagH = 0.0;
|
||||||
public double getLimelightX() {
|
public double getLimelightX() {
|
||||||
return limelightPosX;
|
return limelightTagX;
|
||||||
}
|
}
|
||||||
|
public double getLimelightY() {return limelightTagY;}
|
||||||
|
public double getLimelightZ(){return limelightTagZ;}
|
||||||
|
public double getLimelightH(){return limelightTagH;}
|
||||||
|
|
||||||
public double getLimelightY() {
|
public void relocalize(){
|
||||||
return limelightPosY;
|
setTurret(turrDefault);
|
||||||
|
limelightRead();
|
||||||
}
|
}
|
||||||
|
|
||||||
public int detectObelisk() {
|
public int detectObelisk() {
|
||||||
@@ -140,10 +175,14 @@ public class Turret {
|
|||||||
LLResult result = webcam.getLatestResult();
|
LLResult result = webcam.getLatestResult();
|
||||||
if (result != null && result.isValid()) {
|
if (result != null && result.isValid()) {
|
||||||
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||||
|
double prevTx = -1000;
|
||||||
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||||
|
double currentTx = fiducial.getTargetXDegrees();
|
||||||
|
if (currentTx > prevTx){
|
||||||
obeliskID = fiducial.getFiducialId();
|
obeliskID = fiducial.getFiducialId();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
return obeliskID;
|
return obeliskID;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -235,11 +274,18 @@ public class Turret {
|
|||||||
|
|
||||||
turretAngleDeg += permanentOffset;
|
turretAngleDeg += permanentOffset;
|
||||||
|
|
||||||
|
|
||||||
limelightRead();
|
limelightRead();
|
||||||
// Active correction if we see the target
|
// Active correction if we see the target
|
||||||
if (result.isValid() && !lockOffset && limelightUsed) {
|
if (result.isValid() && !lockOffset && limelightUsed) {
|
||||||
currentTrackOffset += bearingAlign(result);
|
currentTrackOffset += bearingAlign(result);
|
||||||
currentTrackCount++;
|
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);
|
// double bearingError = Math.abs(tagBearingDeg);
|
||||||
//
|
//
|
||||||
// if (bearingError > cameraBearingEqual) {
|
// if (bearingError > cameraBearingEqual) {
|
||||||
@@ -270,9 +316,15 @@ public class Turret {
|
|||||||
// if (currentTrackCount > 20) {
|
// if (currentTrackCount > 20) {
|
||||||
// offset = currentTrackOffset;
|
// offset = currentTrackOffset;
|
||||||
// }
|
// }
|
||||||
|
if (llCoast <= 0) {
|
||||||
|
TELE.addData("LL No Track: ", llCoast);
|
||||||
lightColor = Color.LightRed;
|
lightColor = Color.LightRed;
|
||||||
currentTrackOffset = 0.0;
|
currentTrackOffset = 0.0;
|
||||||
currentTrackCount = 0;
|
currentTrackCount = 0;
|
||||||
|
} else {
|
||||||
|
TELE.addData("LL Coasting: ", llCoast);
|
||||||
|
llCoast--;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Apply accumulated offset
|
// Apply accumulated offset
|
||||||
|
|||||||
@@ -6,7 +6,6 @@ repositories {
|
|||||||
maven { url = 'https://maven.brott.dev/' } //RR
|
maven { url = 'https://maven.brott.dev/' } //RR
|
||||||
maven { url = "https://maven.rowanmcalpin.com/" } //Next FTC
|
maven { url = "https://maven.rowanmcalpin.com/" } //Next FTC
|
||||||
maven { url = "https://repo.dairy.foundation/releases" } //AS
|
maven { url = "https://repo.dairy.foundation/releases" } //AS
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
dependencies {
|
dependencies {
|
||||||
@@ -25,8 +24,6 @@ dependencies {
|
|||||||
implementation 'com.pedropathing:ftc:2.0.6' //PedroCore
|
implementation 'com.pedropathing:ftc:2.0.6' //PedroCore
|
||||||
implementation 'com.pedropathing:telemetry:1.0.0' //PedroTele
|
implementation 'com.pedropathing:telemetry:1.0.0' //PedroTele
|
||||||
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
|
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
|
||||||
|
|
||||||
|
|
||||||
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
|
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
|
||||||
|
|
||||||
implementation 'com.rowanmcalpin.nextftc:core:0.6.2' //NEXT FTC
|
implementation 'com.rowanmcalpin.nextftc:core:0.6.2' //NEXT FTC
|
||||||
|
|||||||
Reference in New Issue
Block a user