36 Commits

Author SHA1 Message Date
KeshavAnandCode
7043274ebd test commit 3 2026-03-18 15:15:38 -05:00
KeshavAnandCode
bd05090afe test commit 2 2026-03-18 15:08:27 -05:00
KeshavAnandCode
369e379eb4 test comit 2026-03-18 15:05:37 -05:00
Keshav Anand
41853e9ad1 Testing new commit stattion 2026-03-09 16:42:00 -05:00
c01edd9308 worlin 2026-02-27 17:25:50 -06:00
ccfac3e123 Merge remote-tracking branch 'origin/LimelightCoast' 2026-02-27 17:22:38 -06:00
395d4439db Commit working auto front 2026-02-27 17:22:01 -06:00
5f33cb4d41 Add limelight coast at 2 seconds. 2026-02-27 17:13:16 -06:00
e92f11bc69 stash 2026-02-27 16:00:38 -06:00
457eaf5feb fixed sxonwe color sorting...jusyt have to have a working auto 2026-02-26 23:17:16 -06:00
dc9886855b sorting ahh thing 2026-02-26 22:18:36 -06:00
194100e3c8 IOoverclocked a whole bunch of chaso @Daniel you got this bro 2026-02-26 17:07:54 -06:00
64b2fed8d6 Auton, hopefully pintpoint works ig 2026-02-24 22:22:03 -06:00
2ccd7f04f8 put in poses for blue 2026-02-23 21:00:14 -06:00
1ae4e1c3ed auto rewritten 2026-02-23 20:29:00 -06:00
7a2b275e66 stash for dany 2026-02-23 19:42:34 -06:00
0264cf2c77 heading relocalization done, need to test for flipping and consistency 2026-02-22 17:55:56 -06:00
f69bffc3ee limelight relocalization of x,y is done. Still need to do heading 2026-02-22 17:44:57 -06:00
09347ce479 color sensor values adjusted 2026-02-22 15:19:43 -06:00
102693d94a turret values adjusted 2026-02-22 15:16:17 -06:00
c2e0b69c55 Added to get limelight positioning 2026-02-21 14:29:10 -06:00
82c16b5402 new method since no longer flippable due to angle being 54 and not 45 2026-02-21 13:51:53 -06:00
5a456e211f new method since no longer flippable due to angle being 54 and not 45 2026-02-21 13:44:31 -06:00
e87c5bb845 fixed a small error 2026-02-21 12:54:27 -06:00
a695f19cc6 fixed a small error 2026-02-21 12:27:25 -06:00
1ad33fd45b targeting angle determined 2026-02-21 12:01:20 -06:00
56b61ee88b gate auto in progress - 30% done 2026-02-20 22:13:52 -06:00
1ee40b472a format of front gate auto complete - V1 2026-02-20 19:38:05 -06:00
3268d5cd02 front gate auto still in progress 2026-02-19 21:19:04 -06:00
44caad767b front gate auto in progress 2026-02-17 18:07:09 -06:00
dd1db74059 stash 2026-02-17 16:21:52 -06:00
7161933d06 back gate auto is like 90% done and changed some things to reduce warnings 2026-02-17 15:45:28 -06:00
0f556a193f back gate auto is like 80% done 2026-02-16 18:03:52 -06:00
85989d54b9 back auto gate cycling in progress 2026-02-15 18:03:37 -06:00
2b9b0a140b lights added to auto 2026-02-15 17:03:49 -06:00
18d9857b7a tubne autob 2026-02-15 16:31:40 -06:00
21 changed files with 1417 additions and 673 deletions

View File

@@ -2,26 +2,47 @@ package org.firstinspires.ftc.teamcode.autonomous;
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.*;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos1;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos2;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos3;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.redObeliskTurrPos0;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.redObeliskTurrPos1;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.redObeliskTurrPos2;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.redObeliskTurrPos3;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spinStartPos;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3b;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
import static org.firstinspires.ftc.teamcode.utils.Turret.turrDefault;
import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
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.Pose2d;
import com.acmerobotics.roadrunner.PoseVelocity2d;
import com.acmerobotics.roadrunner.SequentialAction;
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
import com.acmerobotics.roadrunner.TranslationalVelConstraint;
import com.acmerobotics.roadrunner.Vector2d;
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.LinearOpMode;
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;
@@ -32,32 +53,20 @@ import org.firstinspires.ftc.teamcode.utils.Turret;
@Autonomous(preselectTeleOp = "TeleopV3")
public class Auto_LT_Close extends LinearOpMode {
public static double shoot0Vel = 2300, shoot0Hood = 0.93;
public static double spindexerSpeedIncrease = 0.008;
public static double velGate0Start = 2700, hoodGate0Start = 0.6;
// These values are ADDED to turrDefault
public static double redObeliskTurrPos1 = 0.12;
public static double redObeliskTurrPos2 = 0.13;
public static double redObeliskTurrPos3 = 0.14;
public static double blueObeliskTurrPos1 = -0.12;
public static double blueObeliskTurrPos2 = -0.13;
public static double blueObeliskTurrPos3 = -0.14;
public static double redTurretShootPos = 0.1;
public static double blueTurretShootPos = -0.14;
public static double velGate0End = 2700, hoodGate0End = 0.35;
public static double hood0MoveTime = 2;
public static double spindexerSpeedIncrease = 0.014;
double obeliskTurrPos1 = 0.0;
double obeliskTurrPos2 = 0.0;
double obeliskTurrPos3 = 0.0;
double turretShootPos = 0.0;
public static double shootAllTime = 2;
public static double shootAllTime = 6.0;
public static double intake1Time = 3.3;
public static double intake2Time = 3.8;
public static double intake2Time = 4.2;
public static double intake3Time = 4.2;
public static double intake3Time = 5.4;
public static double flywheel0Time = 1.5;
public static double pickup1Speed = 12;
public static double flywheel0Time = 1.9;
public static double pickup1Speed = 14;
// ---- POSITION TOLERANCES ----
public static double posXTolerance = 5.0;
public static double posYTolerance = 5.0;
@@ -66,7 +75,23 @@ public class Auto_LT_Close extends LinearOpMode {
public static double shoot2Time = 2.5;
public static double shoot3Time = 2.5;
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;
MultipleTelemetry TELE;
@@ -78,8 +103,10 @@ public class Auto_LT_Close extends LinearOpMode {
Targeting targeting;
Targeting.Settings targetingSettings;
AutoActions autoActions;
double x1, y1, h1;
Light light;
int motif = 0;
double x1, y1, h1;
double x2a, y2a, h2a, t2a;
double x2b, y2b, h2b, t2b;
@@ -91,15 +118,22 @@ public class Auto_LT_Close extends LinearOpMode {
double x4b, y4b, h4b;
double xShoot, yShoot, hShoot;
double xGate, yGate, hGate;
double xPrep, yPrep, hPrep;
double xShoot0, yShoot0, hShoot0;
double pickupGateAX, pickupGateAY, pickupGateAH;
double pickupGateBX, pickupGateBY, pickupGateBH;
double xShootGate, yShootGate, hShootGate;
double xLeave, yLeave, hLeave;
private double shoot1Tangent;
double xLeaveGate, yLeaveGate, hLeaveGate;
int ballCycles = 3;
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
TrajectoryActionBuilder shoot0 = null;
@@ -109,6 +143,9 @@ public class Auto_LT_Close extends LinearOpMode {
TrajectoryActionBuilder shoot2 = null;
TrajectoryActionBuilder pickup3 = null;
TrajectoryActionBuilder shoot3 = null;
TrajectoryActionBuilder shoot0ToPickup2 = null;
TrajectoryActionBuilder gateCyclePickup = null;
TrajectoryActionBuilder gateCycleShoot = null;
@Override
public void runOpMode() throws InterruptedException {
@@ -132,20 +169,57 @@ public class Auto_LT_Close extends LinearOpMode {
drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
autoActions = new AutoActions(robot, drive, TELE, servos, flywheel, spindexer, targeting, targetingSettings, turret);
light = Light.getInstance();
servos.setSpinPos(spinStartPos);
light.init(robot.light, spindexer, turret);
autoActions = new AutoActions(robot, drive, TELE, servos, flywheel, spindexer, targeting, targetingSettings, turret, light);
servos.setSpinPos(spindexer_intakePos1);
servos.setTransferPos(transferServo_out);
limelightUsed = false;
robot.light.setPosition(1);
while (opModeInInit()) {
hardwareMap.get(GoBildaPinpointDriver.class, "pinpoint").resetPosAndIMU();
servos.setHoodPos(shoot0Hood);
turret.setTurret(turrDefault);
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);
}
if (gamepad2.crossWasPressed()) {
redAlliance = !redAlliance;
@@ -159,16 +233,25 @@ public class Auto_LT_Close extends LinearOpMode {
turrDefault += 0.01;
}
if (gamepad2.rightBumperWasPressed()){
if (gamepad2.rightBumperWasPressed()) {
ballCycles++;
}
if (gamepad2.leftBumperWasPressed()){
if (gamepad2.leftBumperWasPressed()) {
ballCycles--;
}
if (gamepad2.squareWasPressed()){
turret.pipelineSwitch(1);
if (gamepad2.triangleWasPressed()){
gateCycle = !gateCycle;
}
if (gamepad2.squareWasPressed()) {
drive = new MecanumDrive(hardwareMap,new Pose2d(0,0,0));
robot.limelight.start();
limelightUsed = true;
gamepad2.rumble(500);
}
@@ -199,9 +282,7 @@ public class Auto_LT_Close extends LinearOpMode {
x4b = rx4b;
y4b = ry4b;
h4b = rh4b;
xPrep = rxPrep;
yPrep = ryPrep;
hPrep = rhPrep;
xShoot = rShootX;
yShoot = rShootY;
hShoot = rShootH;
@@ -209,11 +290,27 @@ public class Auto_LT_Close extends LinearOpMode {
yLeave = rLeaveY;
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;
obeliskTurrPos2 = turrDefault + redObeliskTurrPos2;
obeliskTurrPos3 = turrDefault + redObeliskTurrPos3;
turretShootPos = turrDefault + redTurretShootPos;
} else {
robot.light.setPosition(0.6);
@@ -242,9 +339,6 @@ public class Auto_LT_Close extends LinearOpMode {
y4b = by4b;
h4b = bh4b;
xPrep = bxPrep;
yPrep = byPrep;
hPrep = bhPrep;
xShoot = bShootX;
yShoot = bShootY;
hShoot = bShootH;
@@ -252,22 +346,93 @@ public class Auto_LT_Close extends LinearOpMode {
yLeave = bLeaveY;
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;
obeliskTurrPos2 = turrDefault + blueObeliskTurrPos2;
obeliskTurrPos3 = turrDefault + blueObeliskTurrPos3;
turretShootPos = turrDefault + blueTurretShootPos;
}
shoot0 = drive.actionBuilder(new Pose2d(0, 0, 0))
.strafeToLinearHeading(new Vector2d(x1, y1), Math.toRadians(h1));
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))
.strafeToLinearHeading(new Vector2d(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(x2b, y2b), Math.toRadians(h2b),
new TranslationalVelConstraint(pickup1Speed));
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 (ballCycles < 2){
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)))
.strafeToLinearHeading(new Vector2d(x2a, y2a), Math.toRadians(h2a))
.strafeToLinearHeading(new Vector2d(x2b, y2b), Math.toRadians(h2b),
new TranslationalVelConstraint(pickup1Speed));
}
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)))
.strafeToLinearHeading(new Vector2d(xLeave, yLeave), Math.toRadians(hLeave));
} else {
@@ -275,19 +440,6 @@ public class Auto_LT_Close extends LinearOpMode {
.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)))
.strafeToLinearHeading(new Vector2d(x4a, y4a), Math.toRadians(h4a))
.strafeToLinearHeading(new Vector2d(x4b, y4b), Math.toRadians(h4b),
@@ -296,9 +448,19 @@ public class Auto_LT_Close extends LinearOpMode {
shoot3 = drive.actionBuilder(new Pose2d(x4b, y4b, Math.toRadians(h4b)))
.strafeToLinearHeading(new Vector2d(xLeave, yLeave), Math.toRadians(hLeave));
if (withPartner) {
waitToPickupGate = waitToPickupGateWithPartner;
} else {
waitToPickupGate = waitToPickupGateSolo;
}
teleStart = drive.localizer.getPose();
TELE.addData("Red?", redAlliance);
TELE.addData("Turret Default", turrDefault);
TELE.addData("Gate Cycle?", gateCycle);
TELE.addData("Ball Cycles", ballCycles);
TELE.addData("Limelight Started?", limelightUsed);
TELE.addData("Motif", motif);
TELE.update();
}
@@ -309,24 +471,53 @@ public class Auto_LT_Close extends LinearOpMode {
if (opModeIsActive()) {
double stamp = getRuntime();
robot.transfer.setPower(1);
startAuto();
shoot();
if (ballCycles > 0){
cycleStackClose();
shoot();
}
if (gateCycle) {
startAutoGate();
shoot(0.501, 0.501, 0.501);
cycleStackMiddleGate();
shoot(0.501,0.501, 0.501);
if (ballCycles > 1){
cycleStackMiddle();
shoot();
}
while (getRuntime() - stamp < endGateTime) {
cycleGateIntake();
if (getRuntime() - stamp < lastShootTime) {
cycleGateShoot();
shoot(0.501, 0.501, 0.501);
}
}
cycleStackCloseIntakeGate();
if (ballCycles > 2){
cycleStackFar();
shoot();
if (getRuntime() - stamp < lastShootTime) {
cycleStackCloseShootGate();
}
shoot(0.501, 0.501, 0.501);
} else {
startAuto();
shoot(0.501, 0.501,0.501);
if (ballCycles > 0) {
cycleStackClose();
shoot(xShoot, yShoot, hShoot);
}
if (ballCycles > 1) {
cycleStackMiddle();
shoot(xShoot, yShoot, hShoot);
}
if (ballCycles > 2) {
cycleStackFar();
shoot(xLeave, yLeave, hLeave);
}
}
while (opModeIsActive()) {
@@ -346,22 +537,8 @@ public class Auto_LT_Close extends LinearOpMode {
}
void shoot(){
Actions.runBlocking(
new ParallelAction(
autoActions.manageShooterAuto(
shootAllTime,
0.501,
0.501,
0.501,
0.501,
0.501,
false
),
autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease)
)
);
void shoot(double x, double y, double z) {
Actions.runBlocking(autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease, x, y, z));
}
void startAuto() {
@@ -370,55 +547,58 @@ public class Auto_LT_Close extends LinearOpMode {
Actions.runBlocking(
new ParallelAction(
shoot0.build(),
autoActions.manageShooterAuto(
autoActions.prepareShootAll(
0.8,
flywheel0Time,
motif,
x1,
y1,
posXTolerance,
posYTolerance,
h1,
false
h1
)
)
);
}
void cycleStackClose(){
void startAutoGate() {
assert shoot0 != null;
Actions.runBlocking(
new ParallelAction(
shoot0.build(),
autoActions.prepareShootAll(
colorSenseTime,
flywheel0Time,
motif,
xShoot0,
yShoot0,
hShoot0
)
)
);
}
void cycleStackClose() {
Actions.runBlocking(
new ParallelAction(
pickup1.build(),
autoActions.manageShooterAuto(
autoActions.intake(
intake1Time,
x2b,
y2b,
posXTolerance,
posYTolerance,
h2b,
true
),
autoActions.intake(intake1Time),
autoActions.detectObelisk(
intake1Time,
x2b,
y2b,
posXTolerance,
posYTolerance,
obeliskTurrPos1
h2b
)
)
);
motif = turret.getObeliskID();
if (motif == 0) motif = 22;
prevMotif = motif;
double posX;
double posY;
double posH;
if (ballCycles > 1){
if (ballCycles > 1) {
posX = xShoot;
posY = yShoot;
posH = hShoot;
@@ -430,56 +610,36 @@ public class Auto_LT_Close extends LinearOpMode {
Actions.runBlocking(
new ParallelAction(
autoActions.manageShooterAuto(
shoot1.build(),
autoActions.prepareShootAll(
colorSenseTime,
shoot1Time,
motif,
posX,
posY,
posXTolerance,
posYTolerance,
posH,
false
),
shoot1.build(),
autoActions.prepareShootAll(colorSenseTime, shoot1Time, motif)
posH
)
)
);
}
void cycleStackMiddle(){
void cycleStackMiddle() {
Actions.runBlocking(
new ParallelAction(
pickup2.build(),
autoActions.manageShooterAuto(
autoActions.intake(
intake2Time,
x3b,
y3b,
posXTolerance,
posYTolerance,
h3b,
true
),
autoActions.intake(intake2Time),
autoActions.detectObelisk(
intake2Time,
x3b,
y3b,
posXTolerance,
posYTolerance,
obeliskTurrPos2
h3b
)
)
);
motif = turret.getObeliskID();
if (motif == 0) motif = prevMotif;
prevMotif = motif;
double posX;
double posY;
double posH;
if (ballCycles > 2){
if (ballCycles > 2) {
posX = xShoot;
posY = yShoot;
posH = hShoot;
@@ -491,44 +651,28 @@ public class Auto_LT_Close extends LinearOpMode {
Actions.runBlocking(
new ParallelAction(
autoActions.manageShooterAuto(
shoot2.build(),
autoActions.prepareShootAll(
colorSenseTime,
shoot2Time,
motif,
posX,
posY,
posXTolerance,
posYTolerance,
posH,
false
),
shoot2.build(),
autoActions.prepareShootAll(colorSenseTime, shoot2Time, motif)
posH)
)
);
}
void cycleStackFar(){
void cycleStackFar() {
Actions.runBlocking(
new ParallelAction(
pickup3.build(),
autoActions.manageShooterAuto(
autoActions.intake(
intake3Time,
x4b,
y4b,
posXTolerance,
posYTolerance,
h4b,
true
),
autoActions.intake(intake3Time),
autoActions.detectObelisk(
intake3Time,
x4b,
y4b,
posXTolerance,
posYTolerance,
obeliskTurrPos3
h4b
)
)
);
@@ -539,17 +683,129 @@ public class Auto_LT_Close extends LinearOpMode {
Actions.runBlocking(
new ParallelAction(
autoActions.manageShooterAuto(
shoot3.build(),
autoActions.prepareShootAll(
colorSenseTime,
shoot3Time,
motif,
xLeave,
yLeave,
posXTolerance,
posYTolerance,
hLeave,
hLeave
)
)
);
}
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
),
shoot3.build(),
autoActions.prepareShootAll(colorSenseTime, shoot3Time, motif)
)
)
);
}
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
)
)
);
}

View File

@@ -3,26 +3,22 @@ package org.firstinspires.ftc.teamcode.autonomous;
import static org.firstinspires.ftc.teamcode.constants.Back_Poses.*;
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.ServoPositions.spinEndPos;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos1;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos2;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueObeliskTurrPos3;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.blueTurretShootPos;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.redObeliskTurrPos1;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.redObeliskTurrPos2;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.redObeliskTurrPos3;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.redTurretShootPos;
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_in;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
import static org.firstinspires.ftc.teamcode.utils.Targeting.turretInterpolate;
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
import static org.firstinspires.ftc.teamcode.utils.Turret.turrDefault;
import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.FtcDashboard;
import com.acmerobotics.dashboard.config.Config;
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.Pose2d;
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
@@ -35,20 +31,17 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
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;
import java.util.Objects;
@Config
@Autonomous(preselectTeleOp = "TeleopV3")
public class Auto_LT_Far extends LinearOpMode {
public static double shoot0Vel = 3300, shoot0Hood = 0.48;
public static double redTurretShootPos = 0.05;
public static double blueTurretShootPos = -0.05;
double xLeave, yLeave, hLeave;
public int motif = 0;
double turretShootPos = 0.0;
@@ -62,41 +55,39 @@ public class Auto_LT_Far extends LinearOpMode {
Targeting targeting;
Targeting.Settings targetingSettings;
AutoActions autoActions;
Light light;
double xShoot, yShoot, hShoot;
double pickupGateX = 0, pickupGateY = 0, pickupGateH = 0;
double pickupZoneX = 0, pickupZoneY = 0, pickupZoneH = 0;
public static double flywheel0Time = 1.5;
boolean gatePickup = false;
boolean gatePickup = true;
boolean stack3 = true;
double xStackPickupA, yStackPickupA, hStackPickupA;
double xStackPickupB, yStackPickupB, hStackPickupB;
public static int pickupStackSpeed = 12;
public static int pickupStackSpeed = 17;
public static int pickupGateSpeed = 25;
int prevMotif = 0;
public static double spindexerSpeedIncrease = 0.008;
public static double spindexerSpeedIncrease = 0.014;
public static double shootAllTime = 2;
// ---- POSITION TOLERANCES ----
public static double posXTolerance = 5.0;
public static double posYTolerance = 5.0;
public static double shootStackTime = 2;
public static double shootGateTime = 2;
public static double shootGateTime = 2.5;
public static double colorSenseTime = 1;
public static double intakeStackTime = 3.3;
public static double intakeGateTime = 3;
public static double redObeliskTurrPos1 = 0.12;
public static double redObeliskTurrPos2 = 0.13;
public static double redObeliskTurrPos3 = 0.14;
public static double blueObeliskTurrPos1 = -0.12;
public static double blueObeliskTurrPos2 = -0.13;
public static double blueObeliskTurrPos3 = -0.14;
public static double intakeStackTime = 4.5;
public static double intakeGateTime = 8;
double obeliskTurrPos1 = 0.0;
double obeliskTurrPos2 = 0.0;
double obeliskTurrPos3 = 0.0;
public static double endAutoTime = 26;
// initialize path variables here
TrajectoryActionBuilder leave3Ball = null;
TrajectoryActionBuilder leaveFromShoot = null;
TrajectoryActionBuilder pickup3 = null;
TrajectoryActionBuilder shoot3 = null;
TrajectoryActionBuilder pickupGate = null;
TrajectoryActionBuilder shootGate = null;
Pose2d autoStart = new Pose2d(0,0,0);
@Override
@@ -117,6 +108,10 @@ public class Auto_LT_Far extends LinearOpMode {
servos = new Servos(hardwareMap);
light = Light.getInstance();
light.init(robot.light, spindexer, turret);
robot.limelight.start();
robot.limelight.pipelineSwitch(1);
@@ -159,7 +154,7 @@ public class Auto_LT_Far extends LinearOpMode {
autoStart = new Pose2d(autoStartRX, autoStartRY, Math.toRadians(autoStartRH));
drive = new MecanumDrive(hardwareMap, autoStart);
autoActions = new AutoActions(robot, drive, TELE, servos, flywheel, spindexer, targeting, targetingSettings, turret);
autoActions = new AutoActions(robot, drive, TELE, servos, flywheel, spindexer, targeting, targetingSettings, turret, light);
xLeave = rLeaveX;
yLeave = rLeaveY;
@@ -177,6 +172,10 @@ public class Auto_LT_Far extends LinearOpMode {
yStackPickupB = rStackPickupBY;
hStackPickupB = rStackPickupBH;
pickupGateX = rPickupGateX;
pickupGateY = rPickupGateY;
pickupGateH = rPickupGateH;
obeliskTurrPos1 = turrDefault + redObeliskTurrPos1;
obeliskTurrPos2 = turrDefault + redObeliskTurrPos2;
obeliskTurrPos3 = turrDefault + redObeliskTurrPos3;
@@ -185,6 +184,8 @@ public class Auto_LT_Far extends LinearOpMode {
if (gamepad2.squareWasPressed()){
turret.pipelineSwitch(4);
robot.limelight.start();
drive = new MecanumDrive(hardwareMap,new Pose2d(0,0,0));
gamepad2.rumble(500);
}
} else {
@@ -192,7 +193,7 @@ public class Auto_LT_Far extends LinearOpMode {
autoStart = new Pose2d(autoStartBX, autoStartBY, Math.toRadians(autoStartBH));
drive = new MecanumDrive(hardwareMap, autoStart);
autoActions = new AutoActions(robot, drive, TELE, servos, flywheel, spindexer, targeting, targetingSettings, turret);
autoActions = new AutoActions(robot, drive, TELE, servos, flywheel, spindexer, targeting, targetingSettings, turret, light);
xLeave = bLeaveX;
yLeave = bLeaveY;
@@ -210,6 +211,10 @@ public class Auto_LT_Far extends LinearOpMode {
yStackPickupB = bStackPickupBY;
hStackPickupB = bStackPickupBH;
pickupGateX = bPickupGateX;
pickupGateY = bPickupGateY;
pickupGateH = bPickupGateH;
obeliskTurrPos1 = turrDefault + blueObeliskTurrPos1;
obeliskTurrPos2 = turrDefault + blueObeliskTurrPos2;
obeliskTurrPos3 = turrDefault + blueObeliskTurrPos3;
@@ -218,6 +223,8 @@ public class Auto_LT_Far extends LinearOpMode {
if (gamepad2.squareWasPressed()){
turret.pipelineSwitch(2);
robot.limelight.start();
drive = new MecanumDrive(hardwareMap,new Pose2d(0,0,0));
gamepad2.rumble(500);
}
}
@@ -236,6 +243,16 @@ public class Auto_LT_Far extends LinearOpMode {
shoot3 = drive.actionBuilder(new Pose2d(xStackPickupB, yStackPickupB, Math.toRadians(hStackPickupB)))
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), Math.toRadians(hShoot));
pickupGate = drive.actionBuilder(new Pose2d(xShoot, yShoot, Math.toRadians(hShoot)))
.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));
shootGate = drive.actionBuilder(new Pose2d(pickupGateX, pickupGateY, Math.toRadians(pickupGateH)))
.strafeToLinearHeading(new Vector2d(xShoot, yShoot), Math.toRadians(hShoot));
limelightUsed = true;
TELE.addData("Red?", redAlliance);
@@ -253,6 +270,7 @@ public class Auto_LT_Far extends LinearOpMode {
// Currently only shoots; keep this start and modify times and then add extra paths
if (opModeIsActive()) {
double stamp = getRuntime();
robot.transfer.setPower(1);
@@ -264,7 +282,17 @@ public class Auto_LT_Far extends LinearOpMode {
shoot();
}
//TODO: insert code here for gate auto
while (gatePickup && getRuntime() - stamp < endAutoTime){
cycleGatePickupBalls();
if (getRuntime() - stamp > endAutoTime){
break;
}
cycleGatePrepareShoot();
if (getRuntime() - stamp > endAutoTime + shootAllTime + 1){
break;
}
shoot();
}
if (gatePickup || stack3){
leave();
@@ -293,16 +321,7 @@ public class Auto_LT_Far extends LinearOpMode {
void shoot(){
Actions.runBlocking(
new ParallelAction(
autoActions.manageShooterAuto(
shootAllTime,
0.501,
0.501,
0.501,
0.501,
0.501,
false
),
autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease)
autoActions.shootAllAuto(shootAllTime, spindexerSpeedIncrease, 0.501, 0.501, 0.501)
)
);
@@ -316,9 +335,7 @@ public class Auto_LT_Far extends LinearOpMode {
0.501,
0.501,
0.501,
0.501,
0.501,
false
true
)
)
@@ -339,16 +356,12 @@ public class Auto_LT_Far extends LinearOpMode {
Actions.runBlocking(
new ParallelAction(
pickup3.build(),
autoActions.manageShooterAuto(
autoActions.intake(
intakeStackTime,
xStackPickupB,
yStackPickupB,
posXTolerance,
posYTolerance,
hStackPickupB,
true
hStackPickupB
),
autoActions.intake(intakeStackTime),
autoActions.detectObelisk(
intakeStackTime,
xStackPickupB,
@@ -368,17 +381,57 @@ public class Auto_LT_Far extends LinearOpMode {
Actions.runBlocking(
new ParallelAction(
autoActions.manageShooterAuto(
shoot3.build(),
autoActions.prepareShootAll(
colorSenseTime,
shootStackTime,
motif,
xShoot,
yShoot,
hShoot)
)
);
}
void cycleGatePickupBalls(){
Actions.runBlocking(
new ParallelAction(
pickupGate.build(),
autoActions.intake(
intakeStackTime,
pickupGateX,
pickupGateY,
pickupGateH
),
autoActions.detectObelisk(
intakeGateTime,
pickupGateX,
pickupGateY,
posXTolerance,
posYTolerance,
hShoot,
false
),
shoot3.build(),
autoActions.prepareShootAll(colorSenseTime, shootStackTime, motif)
obeliskTurrPos3
)
)
);
motif = turret.getObeliskID();
if (motif == 0) motif = prevMotif;
prevMotif = motif;
}
void cycleGatePrepareShoot(){
Actions.runBlocking(
new ParallelAction(
shootGate.build(),
autoActions.prepareShootAll(
colorSenseTime,
shootGateTime,
motif,
xShoot,
yShoot,
hShoot
)
)
);
}

View File

@@ -10,7 +10,6 @@ import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3b;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
import static org.firstinspires.ftc.teamcode.utils.Targeting.turretInterpolate;
import androidx.annotation.NonNull;
@@ -19,10 +18,15 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
import com.acmerobotics.roadrunner.Action;
import com.acmerobotics.roadrunner.Pose2d;
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
import org.firstinspires.ftc.teamcode.constants.StateEnums;
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
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;
@@ -32,7 +36,7 @@ import org.firstinspires.ftc.teamcode.utils.Turret;
import java.util.Objects;
@Config
public class AutoActions{
public class AutoActions {
Robot robot;
MultipleTelemetry TELE;
Servos servos;
@@ -41,18 +45,18 @@ public class AutoActions{
Spindexer spindexer;
Targeting targeting;
Targeting.Settings targetingSettings;
Light light;
Turret turret;
private int driverSlotGreen = 0;
private int passengerSlotGreen = 0;
private int rearSlotGreen = 0;
private int mostGreenSlot = 0;
private double firstSpindexShootPos = spinStartPos;
public static double firstSpindexShootPos = spinStartPos;
private boolean shootForward = true;
public static double firstShootTime = 0.3;
public int motif = 0;
double spinEndPos = ServoPositions.spinEndPos;
public AutoActions(Robot rob, MecanumDrive dri, MultipleTelemetry tel, Servos ser, Flywheel fly, Spindexer spi, Targeting tar, Targeting.Settings tS, Turret tur){
public AutoActions(Robot rob, MecanumDrive dri, MultipleTelemetry tel, Servos ser, Flywheel fly, Spindexer spi, Targeting tar, Targeting.Settings tS, Turret tur, Light lig) {
this.robot = rob;
this.drive = dri;
this.TELE = tel;
@@ -62,9 +66,17 @@ public class AutoActions{
this.targeting = tar;
this.targetingSettings = tS;
this.turret = tur;
this.light = lig;
}
public Action prepareShootAll(double colorSenseTime, double time, int motif_id) {
public Action prepareShootAll(
double colorSenseTime,
double time,
int motif_id,
double posX,
double posY,
double posH
) {
return new Action() {
double stamp = 0.0;
int ticker = 0;
@@ -73,68 +85,101 @@ public class AutoActions{
boolean decideGreenSlot = false;
void spin1PosFirst(){
void spin1PosFirst() {
firstSpindexShootPos = spindexer_outtakeBall1;
shootForward = true;
spinEndPos = spindexer_outtakeBall3 + 0.1;
spinEndPos = 0.95;
}
void spin2PosFirst(){
void spin2PosFirst() {
firstSpindexShootPos = spindexer_outtakeBall2;
shootForward = false;
spinEndPos = spindexer_outtakeBall3b - 0.1;
spinEndPos = 0.05;
}
void reverseSpin2PosFirst(){
void reverseSpin2PosFirst() {
firstSpindexShootPos = spindexer_outtakeBall2;
shootForward = true;
spinEndPos = 0.95;
}
void spin3PosFirst(){
void spin3PosFirst() {
firstSpindexShootPos = spindexer_outtakeBall3;
shootForward = false;
spinEndPos = spindexer_outtakeBall1 - 0.1;
spinEndPos = 0.05;
}
void oddSpin3PosFirst(){
void oddSpin3PosFirst() {
firstSpindexShootPos = spindexer_outtakeBall3b;
shootForward = true;
spinEndPos = spindexer_outtakeBall2 + 0.1;
spinEndPos = 0.95;
}
Action manageShooter = null;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
if (ticker == 0) {
stamp = System.currentTimeMillis();
manageShooter = manageShooterAuto(time, posX, posY, posH, false);
driverSlotGreen = 0;
passengerSlotGreen = 0;
rearSlotGreen = 0;
}
ticker++;
servos.setTransferPos(transferServo_out);
drive.updatePoseEstimate();
light.setState(StateEnums.LightState.GOAL_LOCK);
teleStart = drive.localizer.getPose();
manageShooter.run(telemetryPacket);
TELE.addData("Most Green Slot", mostGreenSlot);
TELE.addData("Driver Slot Greeness", driverSlotGreen);
TELE.addData("Passenger Slot Greeness", passengerSlotGreen);
TELE.addData("Rear Greeness", rearSlotGreen);
TELE.update();
if ((System.currentTimeMillis() - stamp) < (colorSenseTime * 1000)) {
spindexerWiggle *= -1.0;
servos.setSpinPos(spindexer_intakePos1 + spindexerWiggle);
spindexer.detectBalls(true, true);
if (Objects.equals(spindexer.GetFrontDriverColor(), Spindexer.BallColor.GREEN)) {
driverSlotGreen++;
// Rear Center (Position 1)
double distanceRearCenter = robot.color1.getDistance(DistanceUnit.MM);
if (distanceRearCenter < 52) {
NormalizedRGBA color1RGBA = robot.color1.getNormalizedColors();
double gP1 = color1RGBA.green / (color1RGBA.green + color1RGBA.red + color1RGBA.blue);
if (gP1 >= 0.38) {
rearSlotGreen++;
}
}
if (Objects.equals(spindexer.GetFrontPassengerColor(), Spindexer.BallColor.GREEN)) {
passengerSlotGreen++;
// Front Driver (Position 2)
double distanceFrontDriver = robot.color2.getDistance(DistanceUnit.MM);
if (distanceFrontDriver < 50) {
NormalizedRGBA color2RGBA = robot.color2.getNormalizedColors();
double gP2 = color2RGBA.green / (color2RGBA.green + color2RGBA.red + color2RGBA.blue);
if (gP2 >= 0.4) {
driverSlotGreen++;
}
}
if (Objects.equals(spindexer.GetRearCenterColor(), Spindexer.BallColor.GREEN)) {
rearSlotGreen++;
// Front Passenger (Position 3)
double distanceFrontPassenger = robot.color3.getDistance(DistanceUnit.MM);
if (distanceFrontPassenger < 29) {
NormalizedRGBA color3RGBA = robot.color3.getNormalizedColors();
double gP3 = color3RGBA.green / (color3RGBA.green + color3RGBA.red + color3RGBA.blue);
if (gP3 >= 0.4) {
passengerSlotGreen++;
}
}
spindexer.setIntakePower(1);
spindexer.setIntakePower(-0.1);
decideGreenSlot = true;
@@ -153,29 +198,46 @@ public class AutoActions{
if (motif_id == 21) {
if (mostGreenSlot == 1) {
spin1PosFirst();
firstSpindexShootPos = spindexer_outtakeBall1;
shootForward = true;
spinEndPos = 0.95;
} else if (mostGreenSlot == 2) {
spin2PosFirst();
firstSpindexShootPos = spindexer_outtakeBall2;
shootForward = false;
spinEndPos = 0.05;
} else {
spin3PosFirst();
firstSpindexShootPos = spindexer_outtakeBall3b;
shootForward = true;
spinEndPos = 0.95;
}
} else if (motif_id == 22) {
if (mostGreenSlot == 1) {
spin2PosFirst();
firstSpindexShootPos = spindexer_outtakeBall3b;
shootForward = true;
spinEndPos = 0.95;
} else if (mostGreenSlot == 2) {
spin3PosFirst();
firstSpindexShootPos = spindexer_outtakeBall1;
shootForward = true;
spinEndPos = 0.95;
} else {
reverseSpin2PosFirst();
firstSpindexShootPos = spindexer_outtakeBall1;
shootForward = false;
spinEndPos = 0.03;
}
} else {
if (mostGreenSlot == 1) {
spin3PosFirst();
firstSpindexShootPos = spindexer_outtakeBall3;
shootForward = false;
spinEndPos = 0.05;
} else if (mostGreenSlot == 2) {
oddSpin3PosFirst();
firstSpindexShootPos = spindexer_outtakeBall3b;
shootForward = true;
spinEndPos = 0.95;
} else {
spin1PosFirst();
}
firstSpindexShootPos = spindexer_outtakeBall1;
shootForward = true;
spinEndPos = 0.95; }
}
return true;
@@ -193,54 +255,55 @@ public class AutoActions{
};
}
private boolean doneShooting = false;
public Action shootAllAuto(double shootTime, double spindexSpeed) {
public Action shootAllAuto(double shootTime, double spindexSpeed, double posX, double posY, double posH) {
return new Action() {
int ticker = 1;
double stamp = 0.0;
double velo = 0.0;
int shooterTicker = 0;
Action manageShooter = null;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
velo = flywheel.getVelo();
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 = manageShooterAuto(shootTime, posX, posY, posH, false);
}
ticker++;
manageShooter.run(telemetryPacket);
double prevSpinPos = servos.getSpinCmdPos();
boolean end;
if (shootForward){
end = prevSpinPos > spinEndPos;
if (shootForward) {
end = servos.getSpinPos() > spinEndPos;
} else {
end = prevSpinPos < spinEndPos;
end = servos.getSpinPos() < spinEndPos;
}
if (System.currentTimeMillis() - stamp < shootTime*1000 && (!end || shooterTicker < 2)) {
if (System.currentTimeMillis() - stamp < shootTime * 1000 && (!end || shooterTicker < Spindexer.waitFirstBallTicks + 1)) {
if (!servos.spinEqual(firstSpindexShootPos) && shooterTicker < 3) {
servos.setTransferPos(transferServo_out);
if (!servos.spinEqual(firstSpindexShootPos) && shooterTicker < 1) {
servos.setSpinPos(firstSpindexShootPos);
} else {
servos.setTransferPos(transferServo_in);
shooterTicker++;
if (shootForward) {
Spindexer.whileShooting = true;
if (shootForward && shooterTicker > Spindexer.waitFirstBallTicks) {
servos.setSpinPos(prevSpinPos + spindexSpeed);
} else {
} else if (shooterTicker > Spindexer.waitFirstBallTicks) {
servos.setSpinPos(prevSpinPos - spindexSpeed);
}
@@ -250,10 +313,9 @@ public class AutoActions{
} else {
servos.setTransferPos(transferServo_out);
Spindexer.whileShooting = false;
spindexer.resetSpindexer();
spindexer.processIntake();
doneShooting = true;
return false;
@@ -262,32 +324,119 @@ public class AutoActions{
};
}
public Action intake(double intakeTime) {
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(
double time,
double posX,
double posY,
double posH
) {
return new Action() {
double stamp = 0.0;
int ticker = 0;
Action manageShooter = null;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
if (ticker == 0) {
stamp = System.currentTimeMillis();
manageShooter = manageShooterAuto(time, posX, posY, posH, false);
}
ticker++;
spindexer.processIntake();
spindexer.setIntakePower(1);
light.setState(StateEnums.LightState.BALL_COUNT);
light.update();
spindexer.ballCounterLight();
drive.updatePoseEstimate();
teleStart = drive.localizer.getPose();
return ((System.currentTimeMillis() - stamp) < (intakeTime * 1000)) && !spindexer.isFull();
manageShooter.run(telemetryPacket);
if ((System.currentTimeMillis() - stamp) > (time * 1000)) {
servos.setSpinPos(spindexer_intakePos1);
return false;
} else {
return true;
}
}
};
}
private boolean detectingObelisk = false;
public Action detectObelisk(
double time,
double posX,
@@ -305,6 +454,7 @@ public class AutoActions{
double stamp = 0.0;
int ticker = 0;
int prevMotif = 0;
@Override
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
@@ -315,23 +465,28 @@ public class AutoActions{
if (ticker == 0) {
stamp = System.currentTimeMillis();
turret.pipelineSwitch(1);
ticker++;
}
ticker++;
motif = turret.detectObelisk();
if (prevMotif == motif){
ticker++;
}
prevMotif = motif;
turret.setTurret(turrPos);
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
boolean xDone = posXFallback && Math.abs(currentPose.position.x - posX) < posXTolerance;
boolean yDone = posYFallback && Math.abs(currentPose.position.y - posY) < posYTolerance;
boolean shouldFinish = timeDone || (xDone && yDone) || spindexer.isFull();
boolean shouldFinish = timeDone || (xDone && yDone) || spindexer.isFull() || ticker > 10;
teleStart = currentPose;
if (shouldFinish){
if (redAlliance){
if (shouldFinish) {
if (redAlliance) {
turret.pipelineSwitch(4);
} else {
turret.pipelineSwitch(2);
@@ -350,22 +505,122 @@ public class AutoActions{
double time,
double posX,
double posY,
double posXTolerance,
double posYTolerance,
double posH,
boolean whileIntaking
boolean flywheelSensor
) {
return new Action() {
double stamp = 0.0;
int ticker = 0;
int shootingTicker = 0;
double shootingStamp = 0;
final boolean timeFallback = (time != 0.501);
final boolean posXFallback = (posX != 0.501);
final boolean posYFallback = (posY != 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
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
@@ -390,49 +645,30 @@ public class AutoActions{
double dx = robotX - goalX; // delta x from robot to goal
double dy = robotY - goalY; // delta y from robot to goal
Pose2d deltaPose;
if (posX != 0.501) {
deltaPose = new Pose2d(posX, posY, Math.toRadians(posH));
if (turr == 0.501) {
deltaPose = new Pose2d(dx, dy, robotHeading);
if (!detectingObelisk) {
turret.trackGoal(deltaPose);
}
} else {
deltaPose = new Pose2d(robotX, robotY, robotHeading);
turret.setTurret(turr);
}
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);
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();
flywheel.setPIDF(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F / voltage);
flywheel.manageFlywheel(targetingSettings.flywheelRPM);
flywheel.setPIDF(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F / voltage);
flywheel.manageFlywheel(vel);
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > time * 1000;
boolean xDone = posXFallback && Math.abs(robotX - posX) < posXTolerance;
boolean yDone = posYFallback && Math.abs(robotY - posY) < posYTolerance;
boolean shouldFinish;
if (whileIntaking) {
shouldFinish = timeDone || (xDone && yDone) || spindexer.isFull();
} else {
shouldFinish = timeDone || (xDone && yDone) || doneShooting;
}
boolean timeDone = timeFallback && (System.currentTimeMillis() - stamp) > maxTime * 1000;
teleStart = currentPose;
TELE.addData("Steady?", flywheel.getSteady());
TELE.update();
if (shouldFinish) {
doneShooting = false;
return false;
} else {
return true;
}
return !timeDone;
}
};
}

View File

@@ -1,7 +1,6 @@
package org.firstinspires.ftc.teamcode.constants;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.roadrunner.Pose2d;
@Config
public class Back_Poses {
@@ -11,11 +10,18 @@ public class Back_Poses {
public static double rShootX = 100, rShootY = 55, rShootH = 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 rStackPickupBX = 50, rStackPickupBY = 78, rStackPickupBH = 140.1;
public static double bStackPickupBX = 50, bStackPickupBY = -78, bStackPickupBH = -140.1;
public static double rStackPickupBX = 53, rStackPickupBY = 71, rStackPickupBH = 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 autoStartRX = 103, autoStartRY = 63.5, autoStartRH = 50;
public static double autoStartBX = 103, autoStartBY = -63.5, autoStartBH = -50;

View File

@@ -8,39 +8,55 @@ public class Front_Poses {
public static double rx1 = 20, ry1 = 0.5, rh1 = 0.1;
public static double bx1 = 20, by1 = 0.5, bh1 = 0.1;
public static double bx1 = 20, by1 = -0.5, bh1 = -0.1;
public static double rx2a = 41, ry2a = 18, rh2a = 140;
public static double bx2a = 41, by2a = -18, bh2a = -140;
public static double rx2b = 23, ry2b = 36, rh2b = 140.1;
public static double bx2b = 19, by2b = -40, bh2b = -140.1;
public static double rx2b = 21, ry2b = 34, rh2b = 140.1;
public static double bx2b = 23, by2b = -36, bh2b = -140.1;
public static double rx3a = 55, ry3a = 39, rh3a = 140;
public static double bx3a = 55, by3a = -39, bh3a = -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 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 bx4a = 75, by4a = -53, bh4a = -140;
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 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 bxPrep = 45, byPrep = -10, bhPrep = -50;
public static double rLeaveX = 40, rLeaveY = -7, rLeaveH = 50;
public static double bLeaveX = 40, bLeaveY = 7, bLeaveH = -50;
public static double rLeaveX = 40, rLeaveY = -7, rLeaveH = 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);
}

View File

@@ -5,19 +5,19 @@ import com.acmerobotics.dashboard.config.Config;
@Config
public class ServoPositions {
public static double spindexer_intakePos1 = 0.07; //0.13;
public static double spindexer_intakePos1 = 0.18; //0.13;
public static double spindexer_intakePos2 = 0.27; //0.33;//0.5;
public static double spindexer_intakePos2 = 0.37; //0.33;//0.5;
public static double spindexer_intakePos3 = 0.46; //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_outtakeBall3b = 0.15; //0.65; //0.24;
public static double spindexer_outtakeBall3 = 0.84; //0.65; //0.24;
public static double spindexer_outtakeBall3b = 0.27; //0.65; //0.24;
public static double spindexer_outtakeBall2 = 0.53; //0.46; //0.6;
public static double spindexer_outtakeBall1 = 0.35; //0.27; //0.4;
public static double spinStartPos = 0.22;
public static double spinEndPos = 0.85;
public static double spindexer_outtakeBall2 = 0.66; //0.46; //0.6;
public static double spindexer_outtakeBall1 = 0.47; //0.27; //0.4;
public static double spinStartPos = 0.10;
public static double spinEndPos = 0.95;
public static double shootAllSpindexerSpeedIncrease = 0.014;
@@ -27,19 +27,21 @@ public class ServoPositions {
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_blueClose = 0;
// These values are ADDED to turrDefault
public static double redObeliskTurrPos1 = 0.12;
public static double redObeliskTurrPos2 = 0.13;
public static double redObeliskTurrPos3 = 0.14;
public static double blueObeliskTurrPos1 = -0.12;
public static double blueObeliskTurrPos2 = -0.13;
public static double blueObeliskTurrPos3 = -0.14;
public static double redTurretShootPos = 0.1;
public static double blueTurretShootPos = -0.14;
public static double redObeliskTurrPos0 = -0.35;
public static double redObeliskTurrPos1 = 0.15;
public static double redObeliskTurrPos2 = 0.16;
public static double redObeliskTurrPos3 = 0.17;
public static double blueObeliskTurrPos0 = 0.35;
public static double blueObeliskTurrPos1 = -0.15;
public static double blueObeliskTurrPos2 = -0.16;
public static double blueObeliskTurrPos3 = -0.17;
public static double redTurretShootPos = 0.05;
public static double blueTurretShootPos = -0.05;
}

View File

@@ -5,7 +5,9 @@ import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.canvas.Canvas;
import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
import com.acmerobotics.roadrunner.*;
import com.acmerobotics.roadrunner.AccelConstraint;
import com.acmerobotics.roadrunner.Action;
import com.acmerobotics.roadrunner.Actions;
import com.acmerobotics.roadrunner.AngularVelConstraint;
import com.acmerobotics.roadrunner.DualNum;
import com.acmerobotics.roadrunner.HolonomicController;
@@ -14,12 +16,20 @@ import com.acmerobotics.roadrunner.MinVelConstraint;
import com.acmerobotics.roadrunner.MotorFeedforward;
import com.acmerobotics.roadrunner.Pose2d;
import com.acmerobotics.roadrunner.Pose2dDual;
import com.acmerobotics.roadrunner.PoseVelocity2d;
import com.acmerobotics.roadrunner.PoseVelocity2dDual;
import com.acmerobotics.roadrunner.ProfileAccelConstraint;
import com.acmerobotics.roadrunner.ProfileParams;
import com.acmerobotics.roadrunner.Rotation2d;
import com.acmerobotics.roadrunner.Time;
import com.acmerobotics.roadrunner.TimeTrajectory;
import com.acmerobotics.roadrunner.TimeTurn;
import com.acmerobotics.roadrunner.TrajectoryActionBuilder;
import com.acmerobotics.roadrunner.TrajectoryBuilderParams;
import com.acmerobotics.roadrunner.TurnConstraints;
import com.acmerobotics.roadrunner.Twist2d;
import com.acmerobotics.roadrunner.Twist2dDual;
import com.acmerobotics.roadrunner.Vector2d;
import com.acmerobotics.roadrunner.VelConstraint;
import com.acmerobotics.roadrunner.ftc.DownsampledWriter;
import com.acmerobotics.roadrunner.ftc.Encoder;
@@ -46,13 +56,131 @@ import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumCommandMessage;
import org.firstinspires.ftc.teamcode.libs.RR.messages.MecanumLocalizerInputsMessage;
import org.firstinspires.ftc.teamcode.libs.RR.messages.PoseMessage;
import java.lang.Math;
import java.util.Arrays;
import java.util.LinkedList;
import java.util.List;
@Config
public final class MecanumDrive {
public static Params PARAMS = new Params();
public final MecanumKinematics kinematics = new MecanumKinematics(
PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
public final VelConstraint defaultVelConstraint =
new MinVelConstraint(Arrays.asList(
kinematics.new WheelVelConstraint(PARAMS.maxWheelVel),
new AngularVelConstraint(PARAMS.maxAngVel)
));
public final AccelConstraint defaultAccelConstraint =
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
public final DcMotorEx leftFront, leftBack, rightBack, rightFront;
public final VoltageSensor voltageSensor;
public final LazyImu lazyImu;
public final Localizer localizer;
private final LinkedList<Pose2d> poseHistory = new LinkedList<>();
private final DownsampledWriter estimatedPoseWriter = new DownsampledWriter("ESTIMATED_POSE", 50_000_000);
private final DownsampledWriter targetPoseWriter = new DownsampledWriter("TARGET_POSE", 50_000_000);
private final DownsampledWriter driveCommandWriter = new DownsampledWriter("DRIVE_COMMAND", 50_000_000);
private final DownsampledWriter mecanumCommandWriter = new DownsampledWriter("MECANUM_COMMAND", 50_000_000);
public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
LynxFirmware.throwIfModulesAreOutdated(hardwareMap);
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
}
// TODO: make sure your config has motors with these names (or change them)
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
leftFront = hardwareMap.get(DcMotorEx.class, "fl");
leftBack = hardwareMap.get(DcMotorEx.class, "bl");
rightBack = hardwareMap.get(DcMotorEx.class, "br");
rightFront = hardwareMap.get(DcMotorEx.class, "fr");
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
// TODO: reverse motor directions if needed
//
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
leftBack.setDirection(DcMotorSimple.Direction.REVERSE);
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
voltageSensor = hardwareMap.voltageSensor.iterator().next();
localizer = new PinpointLocalizer(hardwareMap, PARAMS.inPerTick, pose);
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
}
public void setDrivePowers(PoseVelocity2d powers) {
MecanumKinematics.WheelVelocities<Time> wheelVels = new MecanumKinematics(1).inverse(
PoseVelocity2dDual.constant(powers, 1));
double maxPowerMag = 1;
for (DualNum<Time> power : wheelVels.all()) {
maxPowerMag = Math.max(maxPowerMag, power.value());
}
leftFront.setPower(wheelVels.leftFront.get(0) / maxPowerMag);
leftBack.setPower(wheelVels.leftBack.get(0) / maxPowerMag);
rightBack.setPower(wheelVels.rightBack.get(0) / maxPowerMag);
rightFront.setPower(wheelVels.rightFront.get(0) / maxPowerMag);
}
public PoseVelocity2d updatePoseEstimate() {
PoseVelocity2d vel = localizer.update();
poseHistory.add(localizer.getPose());
while (poseHistory.size() > 100) {
poseHistory.removeFirst();
}
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
return vel;
}
private void drawPoseHistory(Canvas c) {
double[] xPoints = new double[poseHistory.size()];
double[] yPoints = new double[poseHistory.size()];
int i = 0;
for (Pose2d t : poseHistory) {
xPoints[i] = t.position.x;
yPoints[i] = t.position.y;
i++;
}
c.setStrokeWidth(1);
c.setStroke("#3F51B5");
c.strokePolyline(xPoints, yPoints);
}
public TrajectoryActionBuilder actionBuilder(Pose2d beginPose) {
return new TrajectoryActionBuilder(
TurnAction::new,
FollowTrajectoryAction::new,
new TrajectoryBuilderParams(
1e-6,
new ProfileParams(
0.25, 0.1, 1e-2
)
),
beginPose, 0.0,
defaultTurnConstraints,
defaultVelConstraint, defaultAccelConstraint
);
}
public static class Params {
// IMU orientation
// TODO: fill in these values based on
@@ -64,62 +192,33 @@ public final class MecanumDrive {
// drive model parameters
public double inPerTick = 0.001978956;
public double lateralInPerTick = 0.0013863732202094405;
public double trackWidthTicks = 6488.883015684446;
public double lateralInPerTick = 0.001367789463080072;
public double trackWidthTicks = 6913.070212622687;
// feedforward parameters (in tick units)
public double kS = 1.2147826978829488;
public double kV = 0.00032;
public double kA = 0.000046;
public double kS = 1.23;
public double kV = 0.00035;
public double kA = 0.00008;
// path profile parameters (in inches)
public double maxWheelVel = 180;
public double maxWheelVel = 70;
public double minProfileAccel = -40;
public double maxProfileAccel = 180;
public double maxProfileAccel = 70;
// turn profile parameters (in radians)
public double maxAngVel = 4* Math.PI; // shared with path
public double maxAngAccel = 4* Math.PI;
public double maxAngVel = 2 *Math.PI; // shared with path
public double maxAngAccel = 2 * Math.PI;
// path controller gains
public double axialGain = 4;
public double lateralGain = 4;
public double headingGain = 4; // shared with turn
public double axialGain = 6.0;
public double lateralGain = 6.0;
public double headingGain = 6.0; // shared with turn
public double axialVelGain = 0.0;
public double lateralVelGain = 0.0;
public double headingVelGain = 0.0; // shared with turn
}
public static Params PARAMS = new Params();
public final MecanumKinematics kinematics = new MecanumKinematics(
PARAMS.inPerTick * PARAMS.trackWidthTicks, PARAMS.inPerTick / PARAMS.lateralInPerTick);
public final TurnConstraints defaultTurnConstraints = new TurnConstraints(
PARAMS.maxAngVel, -PARAMS.maxAngAccel, PARAMS.maxAngAccel);
public final VelConstraint defaultVelConstraint =
new MinVelConstraint(Arrays.asList(
kinematics.new WheelVelConstraint(PARAMS.maxWheelVel),
new AngularVelConstraint(PARAMS.maxAngVel)
));
public final AccelConstraint defaultAccelConstraint =
new ProfileAccelConstraint(PARAMS.minProfileAccel, PARAMS.maxProfileAccel);
public final DcMotorEx leftFront, leftBack, rightBack, rightFront;
public final VoltageSensor voltageSensor;
public final LazyImu lazyImu;
public final Localizer localizer;
private final LinkedList<Pose2d> poseHistory = new LinkedList<>();
private final DownsampledWriter estimatedPoseWriter = new DownsampledWriter("ESTIMATED_POSE", 50_000_000);
private final DownsampledWriter targetPoseWriter = new DownsampledWriter("TARGET_POSE", 50_000_000);
private final DownsampledWriter driveCommandWriter = new DownsampledWriter("DRIVE_COMMAND", 50_000_000);
private final DownsampledWriter mecanumCommandWriter = new DownsampledWriter("MECANUM_COMMAND", 50_000_000);
public class DriveLocalizer implements Localizer {
public final Encoder leftFront, leftBack, rightBack, rightFront;
public final IMU imu;
@@ -144,13 +243,13 @@ public final class MecanumDrive {
}
@Override
public void setPose(Pose2d pose) {
this.pose = pose;
public Pose2d getPose() {
return pose;
}
@Override
public Pose2d getPose() {
return pose;
public void setPose(Pose2d pose) {
this.pose = pose;
}
@Override
@@ -216,63 +315,10 @@ public final class MecanumDrive {
}
}
public MecanumDrive(HardwareMap hardwareMap, Pose2d pose) {
LynxFirmware.throwIfModulesAreOutdated(hardwareMap);
for (LynxModule module : hardwareMap.getAll(LynxModule.class)) {
module.setBulkCachingMode(LynxModule.BulkCachingMode.AUTO);
}
// TODO: make sure your config has motors with these names (or change them)
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
leftFront = hardwareMap.get(DcMotorEx.class, "fl");
leftBack = hardwareMap.get(DcMotorEx.class, "bl");
rightBack = hardwareMap.get(DcMotorEx.class, "br");
rightFront = hardwareMap.get(DcMotorEx.class, "fr");
leftFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
leftBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightBack.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
rightFront.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
// TODO: reverse motor directions if needed
//
leftFront.setDirection(DcMotorSimple.Direction.REVERSE);
leftBack.setDirection(DcMotorSimple.Direction.REVERSE);
// TODO: make sure your config has an IMU with this name (can be BNO or BHI)
// see https://ftc-docs.firstinspires.org/en/latest/hardware_and_software_configuration/configuring/index.html
lazyImu = new LazyHardwareMapImu(hardwareMap, "imu", new RevHubOrientationOnRobot(
PARAMS.logoFacingDirection, PARAMS.usbFacingDirection));
voltageSensor = hardwareMap.voltageSensor.iterator().next();
localizer = new PinpointLocalizer(hardwareMap, PARAMS.inPerTick, pose);
FlightRecorder.write("MECANUM_PARAMS", PARAMS);
}
public void setDrivePowers(PoseVelocity2d powers) {
MecanumKinematics.WheelVelocities<Time> wheelVels = new MecanumKinematics(1).inverse(
PoseVelocity2dDual.constant(powers, 1));
double maxPowerMag = 1;
for (DualNum<Time> power : wheelVels.all()) {
maxPowerMag = Math.max(maxPowerMag, power.value());
}
leftFront.setPower(wheelVels.leftFront.get(0) / maxPowerMag);
leftBack.setPower(wheelVels.leftBack.get(0) / maxPowerMag);
rightBack.setPower(wheelVels.rightBack.get(0) / maxPowerMag);
rightFront.setPower(wheelVels.rightFront.get(0) / maxPowerMag);
}
public final class FollowTrajectoryAction implements Action {
public final TimeTrajectory timeTrajectory;
private double beginTs = -1;
private final double[] xPoints, yPoints;
private double beginTs = -1;
public FollowTrajectoryAction(TimeTrajectory t) {
timeTrajectory = t;
@@ -299,7 +345,16 @@ public final class MecanumDrive {
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);
leftBack.setPower(0);
rightBack.setPower(0);
@@ -308,10 +363,6 @@ public final class MecanumDrive {
return false;
}
Pose2dDual<Time> txWorldTarget = timeTrajectory.get(t);
targetPoseWriter.write(new PoseMessage(txWorldTarget.value()));
PoseVelocity2d robotVelRobot = updatePoseEstimate();
PoseVelocity2dDual<Time> command = new HolonomicController(
PARAMS.axialGain, PARAMS.lateralGain, PARAMS.headingGain,
@@ -342,7 +393,6 @@ public final class MecanumDrive {
p.put("y", localizer.getPose().position.y);
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("yError", error.position.y);
p.put("headingError (deg)", Math.toDegrees(error.heading.toDouble()));
@@ -450,51 +500,4 @@ public final class MecanumDrive {
c.fillCircle(turn.beginPose.position.x, turn.beginPose.position.y, 2);
}
}
public PoseVelocity2d updatePoseEstimate() {
PoseVelocity2d vel = localizer.update();
poseHistory.add(localizer.getPose());
while (poseHistory.size() > 100) {
poseHistory.removeFirst();
}
estimatedPoseWriter.write(new PoseMessage(localizer.getPose()));
return vel;
}
private void drawPoseHistory(Canvas c) {
double[] xPoints = new double[poseHistory.size()];
double[] yPoints = new double[poseHistory.size()];
int i = 0;
for (Pose2d t : poseHistory) {
xPoints[i] = t.position.x;
yPoints[i] = t.position.y;
i++;
}
c.setStrokeWidth(1);
c.setStroke("#3F51B5");
c.strokePolyline(xPoints, yPoints);
}
public TrajectoryActionBuilder actionBuilder(Pose2d beginPose) {
return new TrajectoryActionBuilder(
TurnAction::new,
FollowTrajectoryAction::new,
new TrajectoryBuilderParams(
1e-6,
new ProfileParams(
0.25, 0.1, 1e-2
)
),
beginPose, 0.0,
defaultTurnConstraints,
defaultVelConstraint, defaultAccelConstraint
);
}
}

View File

@@ -16,10 +16,11 @@ import java.util.Objects;
@Config
public final class PinpointLocalizer implements Localizer {
public static class Params {
public double parYTicks = -3765.023079161767; // y position of the parallel encoder (in tick units)
public double perpXTicks = -1962.6377639490684; // x position of the perpendicular encoder (in tick units)
public double parYTicks = -3758.6603115671537; // y position of the parallel encoder (in tick units)
public double perpXTicks = -2088.4296466563774; // x position of the perpendicular encoder (in tick units)
}
public static Params PARAMS = new Params();
public final GoBildaPinpointDriver driver;
@@ -48,6 +49,8 @@ public final class PinpointLocalizer implements Localizer {
txWorldPinpoint = initialPose;
}
@Override
public void setPose(Pose2d pose) {
txWorldPinpoint = pose.times(txPinpointRobot.inverse());

View File

@@ -2,7 +2,6 @@ package org.firstinspires.ftc.teamcode.teleop;
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.ServoPositions.transferServo_in;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
import static org.firstinspires.ftc.teamcode.utils.Targeting.turretInterpolate;
import static org.firstinspires.ftc.teamcode.utils.Turret.limelightUsed;
@@ -46,9 +45,9 @@ public class TeleopV3 extends LinearOpMode {
public double vel = 3000;
public boolean autoVel = true;
public boolean targetingHood = true;
public boolean autoHood = true;
// public boolean autoHood = true;
public double shootStamp = 0.0;
boolean fixedTurret = false;
// boolean fixedTurret = false;
Robot robot;
MultipleTelemetry TELE;
Light light;
@@ -66,16 +65,18 @@ public class TeleopV3 extends LinearOpMode {
boolean reject = false;
double xOffset = 0.0;
double yOffset = 0.0;
double headingOffset = 0.0;
double hOffset = 0.0;
// double headingOffset = 0.0;
int ticker = 0;
boolean autoSpintake = false;
// boolean autoSpintake = false;
boolean enableSpindexerManager = true;
boolean overrideTurr = false;
// boolean overrideTurr = false;
int intakeTicker = 0;
private boolean shootAll = false;
boolean relocalize = false;
@Override
public void runOpMode() throws InterruptedException {
@@ -112,7 +113,6 @@ public class TeleopV3 extends LinearOpMode {
light.setState(StateEnums.LightState.MANUAL);
limelightUsed = true;
robot.light.setPosition(1);
while (opModeInInit()) {
robot.limelight.start();
if (redAlliance) {
@@ -123,6 +123,7 @@ public class TeleopV3 extends LinearOpMode {
light.setManualLightColor(Color.LightBlue);
}
robot.light.setPosition(1);
light.update();
}
@@ -141,12 +142,7 @@ public class TeleopV3 extends LinearOpMode {
//DRIVETRAIN:
drivetrain.drive(
-gamepad1.right_stick_y,
gamepad1.right_stick_x,
gamepad1.left_stick_x,
gamepad1.left_trigger
);
drivetrain.drive(-gamepad1.right_stick_y, gamepad1.right_stick_x, gamepad1.left_stick_x, gamepad1.left_trigger);
if (gamepad1.right_bumper) {
@@ -155,10 +151,10 @@ public class TeleopV3 extends LinearOpMode {
light.setState(StateEnums.LightState.BALL_COUNT);
} else if (gamepad2.triangle){
} else if (gamepad2.triangle) {
light.setState(StateEnums.LightState.BALL_COLOR);
} else {
} else {
light.setState(StateEnums.LightState.GOAL_LOCK);
}
@@ -166,10 +162,11 @@ public class TeleopV3 extends LinearOpMode {
double robX = drive.localizer.getPose().position.x;
double robY = drive.localizer.getPose().position.y;
double robH = drive.localizer.getPose().heading.toDouble();
double robotX = robX - xOffset;
double robotY = robY - yOffset;
double robotHeading = drive.localizer.getPose().heading.toDouble();
double robotX = robX + xOffset;
double robotY = robY + yOffset;
double robotHeading = robH + hOffset;
double goalX = -15;
double goalY = 0;
@@ -178,12 +175,25 @@ public class TeleopV3 extends LinearOpMode {
double dy = robotY - goalY; // delta y from robot to goal
Pose2d deltaPose = new Pose2d(dx, dy, robotHeading);
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
// double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
targetingSettings = targeting.calculateSettings
(robotX, robotY, robotHeading, 0.0, turretInterpolate);
targetingSettings = targeting.calculateSettings(robotX, robotY, robotHeading, 0.0, turretInterpolate);
turret.trackGoal(deltaPose);
//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);
}
//VELOCITY AUTOMATIC
if (autoVel) {
@@ -210,11 +220,12 @@ public class TeleopV3 extends LinearOpMode {
//SHOOTER:
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(vel);
//HOOD:
if (targetingHood) {
servo.setHoodPos(targetingSettings.hoodAngle + autoHoodOffset);
} else {
@@ -251,7 +262,6 @@ public class TeleopV3 extends LinearOpMode {
}
if (enableSpindexerManager) {
//if (!shootAll) {
spindexer.processIntake();
@@ -262,7 +272,6 @@ public class TeleopV3 extends LinearOpMode {
spindexer.setIntakePower(1);
} else if (gamepad1.cross) {
spindexer.setIntakePower(-1);
} else {
spindexer.setIntakePower(0);
}
@@ -284,15 +293,11 @@ public class TeleopV3 extends LinearOpMode {
if (shooterTicker == 0) {
spindexer.prepareShootAllContinous();
//TELE.addLine("preparing to shoot");
// } else if (shooterTicker == 2) {
// else if (shooterTicker == 2) {
// //servo.setTransferPos(transferServo_in);
// spindexer.shootAll();
// TELE.addLine("starting to shoot");
} else if (!spindexer.shootAllComplete()) {
servo.setTransferPos(transferServo_in);
//TELE.addLine("shoot");
} else {
servo.setTransferPos(transferServo_out);
} else if (spindexer.shootAllComplete()) {
//spindexPos = spindexer_intakePos1;
shootAll = false;
spindexer.resetSpindexer();
@@ -345,18 +350,22 @@ public class TeleopV3 extends LinearOpMode {
// Targeting Debug
TELE.addData("robotX", robotX);
TELE.addData("robotY", robotY);
TELE.addData("robotInchesX", targeting.robotInchesX);
TELE.addData("robotInchesY", targeting.robotInchesY);
TELE.addData("Targeting Interpolate", turretInterpolate);
TELE.addData("robot H", robotHeading);
// TELE.addData("robotInchesX", targeting.robotInchesX);
// TELE.addData("robotInchesY", targeting.robotInchesY);
// TELE.addData("Targeting Interpolate", turretInterpolate);
TELE.addData("Targeting GridX", targeting.robotGridX);
TELE.addData("Targeting GridY", targeting.robotGridY);
TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM);
TELE.addData("Targeting HoodAngle", targetingSettings.hoodAngle);
TELE.addData("timeSinceStamp", getRuntime() - shootStamp);
TELE.addData("Voltage", voltage); // returns alleged recorded voltage (not same as driver hub)
// TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM);
// TELE.addData("Targeting HoodAngle", targetingSettings.hoodAngle);
// TELE.addData("timeSinceStamp", getRuntime() - shootStamp);
// TELE.addData("Voltage", voltage); // returns alleged recorded voltage (not same as driver hub)
TELE.addData("Avg Loop Time", loopTimes.getAvgLoopTime());
TELE.addData("Min Loop Time", loopTimes.getMinLoopTimeOneMin());
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();

View File

@@ -7,6 +7,7 @@ import com.acmerobotics.dashboard.config.Config;
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
import org.firstinspires.ftc.teamcode.utils.Robot;
@@ -28,16 +29,20 @@ public class ColorTest extends LinearOpMode {
if (isStopRequested()) return;
while(opModeIsActive()){
double green1 = robot.color1.getNormalizedColors().green;
double blue1 = robot.color1.getNormalizedColors().blue;
double red1 = robot.color1.getNormalizedColors().red;
NormalizedRGBA color1RGBA = robot.color1.getNormalizedColors();
double gP1 = color1RGBA.green / (color1RGBA.green + color1RGBA.red + color1RGBA.blue);
double dist1 = robot.color1.getDistance(DistanceUnit.MM);
color1Distance = (colorFilterAlpha * dist1) + ((1-colorFilterAlpha) * color1Distance);
TELE.addData("Color1 toColor", robot.color1.getNormalizedColors().toColor());
TELE.addData("Color1 green", green1 / (green1 + blue1 + red1));
TELE.addData("Color1 green", gP1);
TELE.addData("Color1 distance (mm)", color1Distance);
// ----- COLOR 2 -----
double green2 = robot.color2.getNormalizedColors().green;
double blue2 = robot.color2.getNormalizedColors().blue;

View File

@@ -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.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.spindexer_intakePos1;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
@@ -37,7 +38,7 @@ public class ShooterTest extends LinearOpMode {
public static double P = 255.0;
public static double I = 0.0;
public static double D = 0.0;
public static double F = 90;
public static double F = 75;
public static double transferPower = 1.0;
public static double hoodPos = 0.501;
public static double turretPos = 0.501;
@@ -128,9 +129,9 @@ public class ShooterTest extends LinearOpMode {
if (hoodPos != 0.501) {
if (enableHoodAutoOpen) {
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)));
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)) + hoodOffset);
} else {
robot.hood.setPosition(hoodPos);
robot.hood.setPosition(hoodPos + hoodOffset);
}
}

View File

@@ -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();
}
}
}
}

View File

@@ -12,15 +12,13 @@ public class Flywheel {
public double velo1 = 0.0;
public double velo2 = 0.0;
double targetVelocity = 0.0;
double previousTargetVelocity = 0.0;
double powPID = 0.0;
boolean steady = false;
public Flywheel (HardwareMap hardwareMap) {
robot = new Robot(hardwareMap);
shooterPIDF1 = new PIDFCoefficients
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F);
shooterPIDF2 = new PIDFCoefficients
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
(Robot.shooterPIDF_P, Robot.shooterPIDF_I, Robot.shooterPIDF_D, Robot.shooterPIDF_F);
}
public double getVelo () {
@@ -52,6 +50,7 @@ public class Flywheel {
if (Math.abs(prevF - f) > voltagePIDFDifference){
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
prevF = f;
}
}
@@ -61,26 +60,23 @@ public class Flywheel {
// Convert from Ticks per Second to RPM
private double TPS_to_RPM (double TPS) { return (TPS*60.0)/28.0;}
public double manageFlywheel(double commandedVelocity) {
public void manageFlywheel(double commandedVelocity) {
if (Math.abs(targetVelocity - commandedVelocity) > 0.0001) {
targetVelocity = commandedVelocity;
// Add code here to set PIDF based on desired RPM
//robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
//robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity));
// Record Current Velocity
velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
velo = Math.max(velo1, velo2);
}
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity));
velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
velo = Math.max(velo1, velo2);
// really should be a running average of the last 5
steady = (Math.abs(commandedVelocity - velo) < 200.0);
steady = (Math.abs(commandedVelocity - velo) < 50);
return powPID;
}
public void update()

View File

@@ -12,7 +12,7 @@ public final class Light {
private static Light instance;
public static double ballColorCycleTime = 1000; //in ms
public static double restingTime = 150; //in ms
public static double restingTime = 125; //in ms
private Servo lightServo;
private LightState state = LightState.DISABLED;

View File

@@ -7,10 +7,10 @@ public class MeasuringLoopTimes {
private double minLoopTime = 999999999999.0;
private double maxLoopTime = 0.0;
private double mainLoopTime = 0.0;
double mainLoopTime = 0.0;
private double MeasurementStart = 0.0;
private double currentTime = 0.0;
double currentTime = 0.0;
private double avgLoopTime = 0.0;
private int avgLoopTimeTicker = 0;

View File

@@ -1,11 +1,9 @@
package org.firstinspires.ftc.teamcode.utils;
import com.acmerobotics.dashboard.config.Config;
import com.arcrobotics.ftclib.hardware.ServoEx;
import com.qualcomm.hardware.limelightvision.Limelight3A;
import com.qualcomm.hardware.rev.RevColorSensorV3;
import com.qualcomm.robotcore.hardware.AnalogInput;
import com.qualcomm.robotcore.hardware.CRServo;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorEx;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
@@ -31,11 +29,11 @@ public class Robot {
public DcMotorEx intake;
public DcMotorEx transfer;
public PIDFCoefficients shooterPIDF;
public double shooterPIDF_P = 255.0;
public double shooterPIDF_I = 0.0;
public double shooterPIDF_D = 0.0;
public double shooterPIDF_F = 90;
public double[] shooterPIDF_StepSizes = {10.0, 1.0, 0.001, 0.0001};
public static double shooterPIDF_P = 255;
public static double shooterPIDF_I = 0.0;
public static double shooterPIDF_D = 0.0;
public static double shooterPIDF_F = 75;
// public double[] shooterPIDF_StepSizes = {10.0, 1.0, 0.001, 0.0001};
public DcMotorEx shooter1;
public DcMotorEx shooter2;
public Servo hood;

View File

@@ -14,8 +14,6 @@ public class Servos {
public static double turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0;
public static double spin_scalar = 1.112;
public static double spin_restPos = 0.155;
public static double turret_scalar = 1.009;
public static double turret_restPos = 0.0;
Robot robot;
PIDFController spinPID;
PIDFController turretPID;
@@ -51,14 +49,13 @@ public class Servos {
return (Math.abs(pos1 - pos2) < 0.005);
}
public double setTransferPos(double pos) {
public void setTransferPos(double pos) {
if (firstTransferPos || !servoPosEqual(pos, prevTransferPos)) {
robot.transferServo.setPosition(pos);
firstTransferPos = false;
}
prevTransferPos = pos;
return pos;
}
public double setSpinPos(double pos) {
@@ -72,29 +69,16 @@ public class Servos {
return pos;
}
public double setHoodPos(double pos){
public void setHoodPos(double pos){
if (firstHoodPos || !servoPosEqual(pos, prevHoodPos)) {
robot.hood.setPosition(pos + hoodOffset);
firstHoodPos = false;
}
prevHoodPos = pos;
return pos;
}
public boolean spinEqual(double pos) {
return Math.abs(pos - this.getSpinPos()) < 0.03;
}
public double getTurrPos() {
return 1.0;
}
public double setTurrPos(double pos) {
return 1.0;
}
public boolean turretEqual(double pos) {
return true;
}
}

View File

@@ -16,6 +16,8 @@ import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_
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.transferServo_in;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_out;
import static org.firstinspires.ftc.teamcode.utils.Servos.spinD;
import static org.firstinspires.ftc.teamcode.utils.Servos.spinF;
import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
@@ -52,6 +54,9 @@ public class Spindexer {
private double prevPos = 0.0;
public double spindexerPosOffset = 0.00;
public static int shootWaitMax = 4;
public static boolean whileShooting = false;
public static int waitFirstBallTicks = 4;
private int shootTicks = 0;
public StateEnums.Motif desiredMotif = StateEnums.Motif.NONE;
// For Use
enum RotatedBallPositionNames {
@@ -182,7 +187,7 @@ public class Spindexer {
distanceFrontPassenger = (colorFilterAlpha * dFrontPassenger) + ((1-colorFilterAlpha) * distanceFrontPassenger);
// Position 1
if (distanceRearCenter < 60) {
if (distanceRearCenter < 48) {
// Mark Ball Found
newPos1Detection = true;
@@ -204,7 +209,7 @@ public class Spindexer {
// Position 2
// Find which ball position this is in the spindexer
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()];
if (distanceFrontDriver < 56) {
if (distanceFrontDriver < 50) {
// reset FoundEmpty because looking for 3 in a row before reset
ballPositions[spindexerBallPos].foundEmpty = 0;
if (detectFrontColor) {
@@ -530,18 +535,26 @@ public class Spindexer {
break;
case SHOOT_PREP_CONTINOUS:
if (servos.spinEqual(spinStartPos)){
if (shootTicks > waitFirstBallTicks){
currentIntakeState = Spindexer.IntakeState.SHOOT_CONTINOUS;
shootTicks++;
} else if (servos.spinEqual(spinStartPos)){
shootTicks++;
servos.setTransferPos(transferServo_in);
} else {
servos.setSpinPos(spinStartPos);
}
break;
case SHOOT_CONTINOUS:
whileShooting = true;
ballPositions[0].isEmpty = false;
ballPositions[1].isEmpty = false;
ballPositions[2].isEmpty = false;
if (servos.getSpinPos() > spinEndPos){
whileShooting = false;
servos.setTransferPos(transferServo_out);
shootTicks = 0;
currentIntakeState = IntakeState.FINDNEXT;
} else {
double spinPos = servos.getSpinCmdPos() + shootAllSpindexerSpeedIncrease;
@@ -658,8 +671,10 @@ public class Spindexer {
return ballPositions[RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.REARCENTER.ordinal()]].ballColor;
}
private double prevPow = 0.501;
private boolean firstIntakePow = true;
public void setIntakePower(double pow){
if (prevPow != 0.501 && prevPow != pow){
if (firstIntakePow || prevPow != pow){
firstIntakePow = false;
robot.intake.setPower(pow);
}
prevPow = pow;

View File

@@ -82,13 +82,19 @@ public class 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) {
Settings recommendedSettings = new Settings(0.0, 0.0);
double cos45 = Math.cos(Math.toRadians(-45));
double sin45 = Math.sin(Math.toRadians(-45));
double rotatedY = (robotX + cancelOffsetX) * sin45 + (robotY + cancelOffsetY) * cos45;
double rotatedX = (robotX + cancelOffsetX) * cos45 - (robotY + cancelOffsetY) * sin45;
if (!redAlliance){
sin54 = Math.sin(Math.toRadians(54));
} else {
sin54 = Math.sin(Math.toRadians(-54));
}
// 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
robotInchesX = rotatedX * unitConversionFactor;
@@ -99,7 +105,17 @@ public class Targeting {
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, 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.
// if near upper or lower quarter or tile interpolate with next tile.
@@ -172,16 +188,6 @@ public class Targeting {
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
if (true) { //!interpolate) {
if ((robotGridY < 6) && (robotGridX < 6)) {

View File

@@ -10,12 +10,11 @@ import com.qualcomm.hardware.limelightvision.LLResult;
import com.qualcomm.hardware.limelightvision.LLResultTypes;
import com.qualcomm.hardware.limelightvision.Limelight3A;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.util.ElapsedTime;
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.constants.StateEnums;
import java.util.ArrayList;
import java.util.List;
@Config
@@ -24,23 +23,21 @@ public class Turret {
public static double turretTolerance = 0.02;
public static double turrPosScalar = 0.00011264432;
public static double turret180Range = 0.4;
public static double turrDefault = 0.37;
public static double turrMin = 0.15;
public static double turrMax = 0.85;
public static double turret180Range = 0.54;
public static double turrDefault = 0.35;
public static double turrMin = 0;
public static double turrMax = 1;
public static boolean limelightUsed = true;
public static double limelightPosOffset = 5;
public static double manualOffset = 0.0;
public static double visionCorrectionGain = 0.08; // Single tunable gain
public static double maxOffsetChangePerCycle = 5.0; // Degrees per cycle
public static double cameraBearingEqual = 0.5; // Deadband
// public static double visionCorrectionGain = 0.08; // Single tunable gain
// public static double maxOffsetChangePerCycle = 5.0; // Degrees per cycle
// public static double cameraBearingEqual = 0.5; // Deadband
// TODO: tune these values for limelight
public static double clampTolerance = 0.03;
// public static double clampTolerance = 0.03;
//public static double B_PID_P = 0.105, B_PID_I = 0.0, B_PID_D = 0.0125;
public static double B_PID_P = 0.066, B_PID_I = 0.0, B_PID_D = 0.007;
public static double B_PID_P = 0.08, B_PID_I = 0.0, B_PID_D = 0.007;
Robot robot;
MultipleTelemetry TELE;
Limelight3A webcam;
@@ -49,7 +46,8 @@ public class Turret {
double limelightPosX = 0.0;
double limelightPosY = 0.0;
LLResult result;
public static double TARGET_POSITION_TOLERANCE = 0.5;
public static double COLOR_OK_TOLERANCE = 2;
boolean bearingAligned = false;
private boolean lockOffset = false;
private int obeliskID = 0;
@@ -57,12 +55,12 @@ public class Turret {
private double currentTrackOffset = 0.0;
private double lightColor = Color.LightRed;
private int currentTrackCount = 0;
private double permanentOffset = 0.0;
double permanentOffset = 0.0;
private int prevPipeline = -1;
private PIDController bearingPID;
PIDController bearingPID;
private double prevTurretPos = 0.0;
private boolean firstTurretPos = true;
public int llCoast = 0;
public int LL_COAST_TICKS = 60;
public Turret(Robot rob, MultipleTelemetry tele, Limelight3A cam) {
this.TELE = tele;
@@ -105,8 +103,12 @@ public class Turret {
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
}
public static double alphaPosConstant = 0.3;
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();
if (result != null) {
if (result.isValid()) {
@@ -118,9 +120,27 @@ public class Turret {
limelightPosX = botpose.getPosition().x;
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() {
@@ -133,12 +153,21 @@ public class Turret {
return ty;
}
Pose3D limelightTagPose;
double limelightTagX = 0.0;
double limelightTagY = 0.0;
double limelightTagZ = 0.0;
double limelightTagH = 0.0;
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() {
return limelightPosY;
public void relocalize(){
setTurret(turrDefault);
limelightRead();
}
public int detectObelisk() {
@@ -146,8 +175,12 @@ public class Turret {
LLResult result = webcam.getLatestResult();
if (result != null && result.isValid()) {
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
double prevTx = -1000;
for (LLResultTypes.FiducialResult fiducial : fiducials) {
obeliskID = fiducial.getFiducialId();
double currentTx = fiducial.getTargetXDegrees();
if (currentTx > prevTx){
obeliskID = fiducial.getFiducialId();
}
}
}
return obeliskID;
@@ -168,16 +201,16 @@ public class Turret {
/*
Param @deltaPos = Pose2d when subtracting robot x, y, heading from goal x, y, heading
*/
private double targetTx = 0;
public static double alphaTX = 0.5;
private double bearingAlign(LLResult llResult) {
double bearingOffset = 0.0;
double targetTx = llResult.getTx(); // How far left or right the target is (degrees)
final double MIN_OFFSET_POWER = 0.15;
final double TARGET_POSITION_TOLERANCE = 1.0;
// LL has 54.5 degree total Horizontal FOV; very edges are not useful.
final double HORIZONTAL_FOV_RANGE = 26.0; // Total usable horizontal degrees from center +/-
final double DRIVE_POWER_REDUCTION = 2.0;
final double COLOR_OK_TOLERANCE = 2.5;
double tx = llResult.getTx(); // How far left or right the target is (degrees)
targetTx = (tx*alphaTX)+(targetTx*(1-alphaTX));
// final double MIN_OFFSET_POWER = 0.15;
// // LL has 54.5 degree total Horizontal FOV; very edges are not useful.
// final double HORIZONTAL_FOV_RANGE = 26.0; // Total usable horizontal degrees from center +/-
// final double DRIVE_POWER_REDUCTION = 2.0;
if (abs(targetTx) < TARGET_POSITION_TOLERANCE) {
bearingAligned = true;
@@ -241,11 +274,18 @@ public class Turret {
turretAngleDeg += permanentOffset;
limelightRead();
// Active correction if we see the target
if (result.isValid() && !lockOffset && limelightUsed) {
currentTrackOffset += bearingAlign(result);
currentTrackCount++;
TELE.addData("LL Tracking: ", llCoast);
// Assume the last tracked value is always better than
// any previous value, even if its not fully aligned.
llCoast = LL_COAST_TICKS;
// double bearingError = Math.abs(tagBearingDeg);
//
// if (bearingError > cameraBearingEqual) {
@@ -276,9 +316,15 @@ public class Turret {
// if (currentTrackCount > 20) {
// offset = currentTrackOffset;
// }
lightColor = Color.LightRed;
currentTrackOffset = 0.0;
currentTrackCount = 0;
if (llCoast <= 0) {
TELE.addData("LL No Track: ", llCoast);
lightColor = Color.LightRed;
currentTrackOffset = 0.0;
currentTrackCount = 0;
} else {
TELE.addData("LL Coasting: ", llCoast);
llCoast--;
}
}
// Apply accumulated offset
@@ -293,7 +339,7 @@ public class Turret {
targetTurretPos = Math.max(turrMin, Math.min(targetTurretPos, turrMax));
// Interpolate towards target position
double currentPos = getTurrPos();
// double currentPos = getTurrPos();
double turretPos = targetTurretPos;
if (targetTurretPos == turrMin) {
@@ -303,7 +349,9 @@ public class Turret {
}
// Set servo positions
setTurret(turretPos + manualOffset);
if (!Spindexer.whileShooting || abs(targetTx) > COLOR_OK_TOLERANCE){
setTurret(turretPos + manualOffset);
}
/* ---------------- TELEMETRY ---------------- */

View File

@@ -6,7 +6,6 @@ repositories {
maven { url = 'https://maven.brott.dev/' } //RR
maven { url = "https://maven.rowanmcalpin.com/" } //Next FTC
maven { url = "https://repo.dairy.foundation/releases" } //AS
}
dependencies {
@@ -25,8 +24,6 @@ dependencies {
implementation 'com.pedropathing:ftc:2.0.6' //PedroCore
implementation 'com.pedropathing:telemetry:1.0.0' //PedroTele
implementation 'com.bylazar:fullpanels:1.0.2' //Panels
implementation 'org.ftclib.ftclib:core:2.1.1' // FTC LIB
implementation 'com.rowanmcalpin.nextftc:core:0.6.2' //NEXT FTC