14 Commits

Author SHA1 Message Date
4050a354f7 Update TelopV3 and Targeting for merge conflicts. 2026-01-23 20:19:21 -06:00
f20e640c62 Merge remote-tracking branch 'origin/master' into Targeting
# Conflicts:
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/TeleopV3.java
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/TurretTest.java
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/Turret.java
2026-01-22 22:13:07 -06:00
c2e9d8fa87 Merge remote-tracking branch 'origin/Targeting' into Targeting 2026-01-22 22:00:41 -06:00
46a5366a4a Add Auto ball detect on startup to spindexer to detect how many balls are already in spindexer on power on. 2026-01-22 21:59:58 -06:00
fbdeb6e291 Turret works y8ippee horray hurrah ig 2026-01-22 21:04:25 -06:00
abhiram vishnubhotla
298b7bca8c Merge pull request #13 from Technical-Turbulence-FTC/feature/interpolation
Feature/interpolation
2026-01-22 20:21:05 -06:00
2f0fcad128 updated interpolation in teleop 2026-01-22 20:06:08 -06:00
45199b952b added interpolation 2026-01-22 20:03:00 -06:00
76ceb91fb7 Merge branch 'Targeting' of https://github.com/Technical-Turbulence-FTC/DecodeFTCMain into turret-refactor-updates 2026-01-22 19:28:42 -06:00
b55d44ae97 Merge branch 'Targeting' of https://github.com/Technical-Turbulence-FTC/DecodeFTCMain into turret-refactor-updates 2026-01-21 20:01:22 -06:00
50212015e3 trackGoal expected robot centric view, but was fed a field centric view. simple trig to use a deltaPos instead of just pos 2026-01-21 19:04:30 -06:00
c271c88e45 Merge branch 'master' of https://github.com/Technical-Turbulence-FTC/DecodeFTCMain into test/continuous_ll_track 2026-01-21 18:36:06 -06:00
a3068cea2e Merge branch 'SpindexerRefactor' of https://github.com/Technical-Turbulence-FTC/DecodeFTCMain into test/continuous_ll_track 2026-01-20 19:17:16 -06:00
f1d4bb9d24 continous ll tracking, TEST 2026-01-19 10:38:34 -06:00
7 changed files with 155 additions and 118 deletions

View File

@@ -12,7 +12,7 @@ public class Poses {
public static double relativeGoalHeight = goalHeight - turretHeight; public static double relativeGoalHeight = goalHeight - turretHeight;
public static Pose2d goalPose = new Pose2d(-15, 0, 0); public static Pose2d goalPose = new Pose2d(-10, 0, 0);
public static double rx1 = 40, ry1 = -7, rh1 = 0; public static double rx1 = 40, ry1 = -7, rh1 = 0;
public static double rx2a = 41, ry2a = 18, rh2a = Math.toRadians(140); public static double rx2a = 41, ry2a = 18, rh2a = Math.toRadians(140);
@@ -38,6 +38,6 @@ public class Poses {
public static double bx4b = 48, by4b = -79, bh4b = Math.toRadians(-140); public static double bx4b = 48, by4b = -79, bh4b = Math.toRadians(-140);
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this
public static Pose2d teleStart = new Pose2d(rx1, ry1, rh1); public static Pose2d teleStart = new Pose2d(0, 0, 0);
} }

View File

@@ -1,11 +1,9 @@
package org.firstinspires.ftc.teamcode.teleop; package org.firstinspires.ftc.teamcode.teleop;
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart; import static org.firstinspires.ftc.teamcode.constants.Poses.teleStart;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1; import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.transferServo_in; 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.constants.ServoPositions.transferServo_out;
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.turrDefault;
import static org.firstinspires.ftc.teamcode.utils.Servos.spinD; 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.spinF;
import static org.firstinspires.ftc.teamcode.utils.Servos.spinI; import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
@@ -21,7 +19,6 @@ import com.acmerobotics.roadrunner.TranslationalVelConstraint;
import com.acmerobotics.roadrunner.Vector2d; import com.acmerobotics.roadrunner.Vector2d;
import com.acmerobotics.roadrunner.ftc.Actions; import com.acmerobotics.roadrunner.ftc.Actions;
import com.arcrobotics.ftclib.controller.PIDFController; import com.arcrobotics.ftclib.controller.PIDFController;
import com.qualcomm.hardware.limelightvision.LLResult;
import com.qualcomm.hardware.lynx.LynxModule; import com.qualcomm.hardware.lynx.LynxModule;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode; import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.eventloop.opmode.TeleOp; import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
@@ -29,11 +26,13 @@ import com.qualcomm.robotcore.hardware.DcMotor;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit; import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive; import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
import org.firstinspires.ftc.teamcode.utils.Flywheel; import org.firstinspires.ftc.teamcode.utils.Flywheel;
import org.firstinspires.ftc.teamcode.utils.Robot; import org.firstinspires.ftc.teamcode.utils.Robot;
import org.firstinspires.ftc.teamcode.utils.Servos; import org.firstinspires.ftc.teamcode.utils.Servos;
import org.firstinspires.ftc.teamcode.utils.Spindexer; import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting; import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utils.Turret;
import java.util.ArrayList; import java.util.ArrayList;
import java.util.List; import java.util.List;
@@ -121,6 +120,7 @@ public class TeleopV3 extends LinearOpMode {
private double transferStamp = 0.0; private double transferStamp = 0.0;
private int tickerA = 1; private int tickerA = 1;
private boolean transferIn = false; private boolean transferIn = false;
boolean turretInterpolate = false;
public static double velPrediction(double distance) { public static double velPrediction(double distance) {
if (distance < 30) { if (distance < 30) {
@@ -152,7 +152,7 @@ public class TeleopV3 extends LinearOpMode {
drive = new MecanumDrive(hardwareMap, teleStart); drive = new MecanumDrive(hardwareMap, teleStart);
spindexer = new Spindexer(hardwareMap); spindexer = new Spindexer(hardwareMap);
targeting = new Targeting(); targeting = new Targeting();
targetingSettings = new Targeting.Settings(0.0,0.0); targetingSettings = new Targeting.Settings(0.0, 0.0);
PIDFController tController = new PIDFController(tp, ti, td, tf); PIDFController tController = new PIDFController(tp, ti, td, tf);
@@ -166,6 +166,12 @@ public class TeleopV3 extends LinearOpMode {
// robot.limelight.start(); // robot.limelight.start();
AprilTagWebcam webcam = new AprilTagWebcam();
webcam.init(robot, TELE);
Turret turret = new Turret(robot, TELE, webcam);
waitForStart();
waitForStart(); waitForStart();
if (isStopRequested()) return; if (isStopRequested()) return;
@@ -379,39 +385,21 @@ public class TeleopV3 extends LinearOpMode {
double robotY = robY - yOffset; double robotY = robY - yOffset;
double robotHeading = drive.localizer.getPose().heading.toDouble(); double robotHeading = drive.localizer.getPose().heading.toDouble();
double goalX = -10; double goalX = -15;
double goalY = 0; double goalY = 0;
double dx = goalX - robotX; // delta x from robot to goal double dx = robotX - goalX; // delta x from robot to goal
double dy = goalY - robotY; // delta y from robot to goal 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);
desiredTurretAngle = (Math.toDegrees(Math.atan2(dy, dx)) + 360) % 360;
desiredTurretAngle += manualOffset + error;
offset = desiredTurretAngle - 180 - (Math.toDegrees(robotHeading - headingOffset));
if (offset > 135) {
offset -= 360;
}
double pos = turrDefault;
TELE.addData("offset", offset);
pos -= offset * ((double) 1 / 360);
if (pos < 0.13) {
pos = 0.13;
} else if (pos > 0.83) {
pos = 0.83;
}
targetingSettings = targeting.calculateSettings targetingSettings = targeting.calculateSettings
(robotX,robotY,robotHeading,0.0); (robotX,robotY,robotHeading,0.0, turretInterpolate);
turret.trackGoal(deltaPose);
webcam.update();
//VELOCITY AUTOMATIC //VELOCITY AUTOMATIC
if (targetingVel) { if (targetingVel) {
@@ -443,8 +431,6 @@ public class TeleopV3 extends LinearOpMode {
//TODO: test the camera teleop code //TODO: test the camera teleop code
TELE.addData("posS2", pos);
// if (y < 0.3 && y > -0.3 && x < 0.3 && x > -0.3 && rx < 0.3 && rx > -0.3) { //not moving // if (y < 0.3 && y > -0.3 && x < 0.3 && x > -0.3 && rx < 0.3 && rx > -0.3) { //not moving
// double bearing; // double bearing;
// //
@@ -468,27 +454,6 @@ public class TeleopV3 extends LinearOpMode {
// overrideTurr = false; // overrideTurr = false;
// } // }
if (!overrideTurr) {
turretPos = pos;
}
TELE.addData("posS3", turretPos);
if (manualTurret) {
pos = turrDefault + (manualOffset / 100) + error;
}
if (!overrideTurr) {
turretPos = pos;
}
if (Math.abs(gamepad2.left_stick_x)>0.2) {
manualOffset += 1.35 * gamepad2.left_stick_x;
}
robot.turr1.setPosition(pos);
robot.turr2.setPosition(1 - pos);
//HOOD: //HOOD:
if (targetingHood) { if (targetingHood) {
@@ -873,6 +838,7 @@ public class TeleopV3 extends LinearOpMode {
TELE.addData( "robotY", robotY); TELE.addData( "robotY", robotY);
TELE.addData("robotInchesX", targeting.robotInchesX); TELE.addData("robotInchesX", targeting.robotInchesX);
TELE.addData( "robotInchesY", targeting.robotInchesY); TELE.addData( "robotInchesY", targeting.robotInchesY);
TELE.addData("Targeting Interpolate", turretInterpolate);
TELE.addData("Targeting GridX", targeting.robotGridX); TELE.addData("Targeting GridX", targeting.robotGridX);
TELE.addData("Targeting GridY", targeting.robotGridY); TELE.addData("Targeting GridY", targeting.robotGridY);
TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM); TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM);

View File

@@ -30,12 +30,20 @@ public class TurretTest extends LinearOpMode {
Turret turret = new Turret(robot, TELE, webcam); Turret turret = new Turret(robot, TELE, webcam);
waitForStart(); waitForStart();
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(10, 0,0));
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(15, 0,0));
while(opModeIsActive()){ while(opModeIsActive()){
drive.updatePoseEstimate(); drive.updatePoseEstimate();
turret.trackGoal(drive.localizer.getPose()); turret.trackGoal(drive.localizer.getPose());
webcam.update();
webcam.displayAllTelemetry();
TELE.update();
} }
} }

View File

@@ -79,8 +79,10 @@ public class Robot {
shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F); shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F);
shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER); shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF); shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
shooter1.setVelocity(1400);
shooter2.setMode(DcMotor.RunMode.RUN_USING_ENCODER); shooter2.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF); shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
shooter2.setVelocity(1400);
hood = hardwareMap.get(Servo.class, "hood"); hood = hardwareMap.get(Servo.class, "hood");

View File

@@ -52,7 +52,9 @@ public class Spindexer {
} }
enum IntakeState { enum IntakeState {
UNKNOWN, UNKNOWN_START,
UNKNOWN_MOVE,
UNKNOWN_DETECT,
INTAKE, INTAKE,
FINDNEXT, FINDNEXT,
MOVING, MOVING,
@@ -62,8 +64,8 @@ public class Spindexer {
SHOOTWAIT, SHOOTWAIT,
}; };
public IntakeState currentIntakeState = IntakeState.UNKNOWN; public IntakeState currentIntakeState = IntakeState.UNKNOWN_START;
public int unknownColorDetect = 0;
enum BallColor { enum BallColor {
UNKNOWN, UNKNOWN,
GREEN, GREEN,
@@ -131,13 +133,13 @@ public class Spindexer {
for (int i = 0; i < 3; i++) { for (int i = 0; i < 3; i++) {
resetBallPosition(i); resetBallPosition(i);
} }
currentIntakeState = IntakeState.UNKNOWN; currentIntakeState = IntakeState.UNKNOWN_START;
} }
// Detects if a ball is found and what color. // Detects if a ball is found and what color.
// Returns true is there was a new ball found in Position 1 // Returns true is there was a new ball found in Position 1
// FIXIT: Reduce number of times that we read the color sensors for loop times. // FIXIT: Reduce number of times that we read the color sensors for loop times.
public boolean detectBalls() { public boolean detectBalls(boolean detectRearColor, boolean detectFrontColor) {
boolean newPos1Detection = false; boolean newPos1Detection = false;
int spindexerBallPos = 0; int spindexerBallPos = 0;
@@ -153,6 +155,7 @@ public class Spindexer {
// Mark Ball Found // Mark Ball Found
newPos1Detection = true; newPos1Detection = true;
if (detectRearColor) {
// Detect which color // Detect which color
double green = robot.color1.getNormalizedColors().green; double green = robot.color1.getNormalizedColors().green;
double red = robot.color1.getNormalizedColors().red; double red = robot.color1.getNormalizedColors().red;
@@ -167,24 +170,26 @@ public class Spindexer {
ballPositions[commandedIntakePosition].ballColor = BallColor.GREEN; // purple ballPositions[commandedIntakePosition].ballColor = BallColor.GREEN; // purple
} }
} }
}
// Position 2 // Position 2
// Find which ball position this is in the spindexer // Find which ball position this is in the spindexer
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()]; spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()];
if (distanceFrontDriver < 60) { if (distanceFrontDriver < 60) {
// reset FoundEmpty because looking for 3 in a row before reset // reset FoundEmpty because looking for 3 in a row before reset
ballPositions[spindexerBallPos].foundEmpty = 0; ballPositions[spindexerBallPos].foundEmpty = 0;
// FIXIT: Comment out for now due to loop time concerns if (detectFrontColor) {
// double green = robot.color2.getNormalizedColors().green; double green = robot.color2.getNormalizedColors().green;
// double red = robot.color2.getNormalizedColors().red; double red = robot.color2.getNormalizedColors().red;
// double blue = robot.color2.getNormalizedColors().blue; double blue = robot.color2.getNormalizedColors().blue;
//
// double gP = green / (green + red + blue);
// if (gP >= 0.4) { double gP = green / (green + red + blue);
// b2 = 2; // purple
// } else { if (gP >= 0.4) {
// b2 = 1; // green ballPositions[spindexerBallPos].ballColor = BallColor.PURPLE; // purple
// } } else {
ballPositions[spindexerBallPos].ballColor = BallColor.GREEN; // purple
}
}
} else { } else {
if (!ballPositions[spindexerBallPos].isEmpty) { if (!ballPositions[spindexerBallPos].isEmpty) {
if (ballPositions[spindexerBallPos].foundEmpty > 3) { if (ballPositions[spindexerBallPos].foundEmpty > 3) {
@@ -201,18 +206,19 @@ public class Spindexer {
// reset FoundEmpty because looking for 3 in a row before reset // reset FoundEmpty because looking for 3 in a row before reset
ballPositions[spindexerBallPos].foundEmpty = 0; ballPositions[spindexerBallPos].foundEmpty = 0;
// FIXIT: Comment out for now due to loop time concerns if (detectFrontColor) {
// double green = robot.color3.getNormalizedColors().green; double green = robot.color3.getNormalizedColors().green;
// double red = robot.color3.getNormalizedColors().red; double red = robot.color3.getNormalizedColors().red;
// double blue = robot.color3.getNormalizedColors().blue; double blue = robot.color3.getNormalizedColors().blue;
// double gP = green / (green + red + blue); double gP = green / (green + red + blue);
// if (gP >= 0.4) { if (gP >= 0.4) {
// b3 = 2; // purple ballPositions[spindexerBallPos].ballColor = BallColor.PURPLE; // purple
// } else { } else {
// b3 = 1; // green ballPositions[spindexerBallPos].ballColor = BallColor.GREEN; // purple
// } }
}
} else { } else {
if (!ballPositions[spindexerBallPos].isEmpty) { if (!ballPositions[spindexerBallPos].isEmpty) {
if (ballPositions[spindexerBallPos].foundEmpty > 3) { if (ballPositions[spindexerBallPos].foundEmpty > 3) {
@@ -255,15 +261,35 @@ public class Spindexer {
public boolean processIntake() { public boolean processIntake() {
switch (currentIntakeState) { switch (currentIntakeState) {
case UNKNOWN: case UNKNOWN_START:
// For now just set position ONE if UNKNOWN // For now just set position ONE if UNKNOWN
commandedIntakePosition = 0; commandedIntakePosition = 0;
servos.setSpinPos(intakePositions[0]); servos.setSpinPos(intakePositions[0]);
currentIntakeState = Spindexer.IntakeState.MOVING; currentIntakeState = Spindexer.IntakeState.UNKNOWN_MOVE;
break;
case UNKNOWN_MOVE:
// Stopping when we get to the new position
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
currentIntakeState = Spindexer.IntakeState.UNKNOWN_DETECT;
stopSpindexer();
detectBalls(true, true);
unknownColorDetect = 0;
} else {
// Keep moving the spindexer
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
}
break;
case UNKNOWN_DETECT:
if (unknownColorDetect >5) {
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
} else {
detectBalls(true, true);
unknownColorDetect++;
}
break; break;
case INTAKE: case INTAKE:
// Ready for intake and Detecting a New Ball // Ready for intake and Detecting a New Ball
if (detectBalls()) { if (detectBalls(true, false)) {
ballPositions[commandedIntakePosition].isEmpty = false; ballPositions[commandedIntakePosition].isEmpty = false;
currentIntakeState = Spindexer.IntakeState.FINDNEXT; currentIntakeState = Spindexer.IntakeState.FINDNEXT;
} else { } else {
@@ -311,7 +337,7 @@ public class Spindexer {
if (servos.spinEqual(intakePositions[commandedIntakePosition])) { if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
currentIntakeState = Spindexer.IntakeState.INTAKE; currentIntakeState = Spindexer.IntakeState.INTAKE;
stopSpindexer(); stopSpindexer();
detectBalls(); detectBalls(false, false);
} else { } else {
// Keep moving the spindexer // Keep moving the spindexer
moveSpindexerToPos(intakePositions[commandedIntakePosition]); moveSpindexerToPos(intakePositions[commandedIntakePosition]);
@@ -320,7 +346,7 @@ public class Spindexer {
case FULL: case FULL:
// Double Check Colors // Double Check Colors
detectBalls(); detectBalls(false, false); // Minimize hardware calls
if (ballPositions[0].isEmpty || ballPositions[1].isEmpty || ballPositions[2].isEmpty) { if (ballPositions[0].isEmpty || ballPositions[1].isEmpty || ballPositions[2].isEmpty) {
// Error handling found an empty spot, get it ready for a ball // Error handling found an empty spot, get it ready for a ball
currentIntakeState = Spindexer.IntakeState.FINDNEXT; currentIntakeState = Spindexer.IntakeState.FINDNEXT;
@@ -378,7 +404,7 @@ public class Spindexer {
if (servos.spinEqual(intakePositions[commandedIntakePosition])) { if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
currentIntakeState = Spindexer.IntakeState.INTAKE; currentIntakeState = Spindexer.IntakeState.INTAKE;
stopSpindexer(); stopSpindexer();
detectBalls(); detectBalls(true, false);
} else { } else {
// Keep moving the spindexer // Keep moving the spindexer
moveSpindexerToPos(intakePositions[commandedIntakePosition]); moveSpindexerToPos(intakePositions[commandedIntakePosition]);

View File

@@ -84,28 +84,58 @@ public class Targeting {
{ {
} }
public Settings calculateSettings(double robotX, double robotY, double robotHeading, double robotVelocity) { public Settings calculateSettings(double robotX, double robotY, double robotHeading, double robotVelocity, boolean interpolate) {
Settings recommendedSettings = new Settings(0.0, 0.0); Settings recommendedSettings = new Settings(0.0, 0.0);
double cos45 = Math.cos(Math.toRadians(-45)); double cos45 = Math.cos(Math.toRadians(-45));
double sin45 = Math.sin(Math.toRadians(-45)); double sin45 = Math.sin(Math.toRadians(-45));
double rotatedY = (robotX -40.0) * sin45 + (robotY +7.0) * cos45; double rotatedY = (robotX - 40.0) * sin45 + (robotY + 7.0) * cos45;
double rotatedX = (robotX -40.0) * cos45 - (robotY +7.0) * sin45; double rotatedX = (robotX - 40.0) * cos45 - (robotY + 7.0) * sin45;
// Convert robot coordinates to inches // Convert robot coordinates to inches
robotInchesX = rotatedX * unitConversionFactor; robotInchesX = rotatedX * unitConversionFactor;
robotInchesY = rotatedY * unitConversionFactor; robotInchesY = rotatedY * unitConversionFactor;
// Find approximate location in the grid // Find approximate location in the grid
robotGridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) +1); int gridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) + 1);
robotGridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize)); int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
// Use Grid Location to perform lookup //clamp
// Keep it simple for now but may want to interpolate results robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
// basic search
if(!interpolate) {
if ((robotGridY < 6) && (robotGridX <6)) { if ((robotGridY < 6) && (robotGridX <6)) {
recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridY][robotGridX].flywheelRPM; recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridY][robotGridX].flywheelRPM;
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridY][robotGridX].hoodAngle; recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridY][robotGridX].hoodAngle;
} }
return recommendedSettings; return recommendedSettings;
} else {
// bilinear interpolation
int x0 = robotGridX;
int x1 = Math.min(x0 + 1, KNOWNTARGETING[0].length - 1);
int y0 = gridY;
int y1 = Math.min(y0 + 1, KNOWNTARGETING.length - 1);
double x = (robotInchesX - (x0 * tileSize)) / tileSize;
double y = (robotInchesY - (y0 * tileSize)) / tileSize;
double rpm00 = KNOWNTARGETING[y0][x0].flywheelRPM;
double rpm10 = KNOWNTARGETING[y0][x1].flywheelRPM;
double rpm01 = KNOWNTARGETING[y1][x0].flywheelRPM;
double rpm11 = KNOWNTARGETING[y1][x1].flywheelRPM;
double angle00 = KNOWNTARGETING[y0][x0].hoodAngle;
double angle10 = KNOWNTARGETING[y0][x1].hoodAngle;
double angle01 = KNOWNTARGETING[y1][x0].hoodAngle;
double angle11 = KNOWNTARGETING[y1][x1].hoodAngle;
recommendedSettings.flywheelRPM = (1 - x) * (1 - y) * rpm00 + x * (1 - y) * rpm10 + (1 - x) * y * rpm01 + x * y * rpm11;
recommendedSettings.hoodAngle = (1 - x) * (1 - y) * angle00 + x * (1 - y) * angle10 + (1 - x) * y * angle01 + x * y * angle11;
return recommendedSettings;
}
} }
} }

View File

@@ -13,12 +13,14 @@ public class Turret {
public static double turretTolerance = 0.02; public static double turretTolerance = 0.02;
public static double turrPosScalar = 1.009; public static double turrPosScalar = 1.009;
public static double turret180Range = 0.6; public static double turret180Range = 0.4;
public static double turrDefault = 0.4; public static double turrDefault = 0.4;
public static double cameraBearingEqual = 1.5; public static double cameraBearingEqual = 1;
public static double errorLearningRate = 2; public static double errorLearningRate = 0.15;
public static double turrMin = 0.2; public static double turrMin = 0.2;
public static double turrMax = 0.8; public static double turrMax = 0.8;
public static double deltaAngleThreshold = 0.02;
public static double angleMultiplier = 0.0;
Robot robot; Robot robot;
MultipleTelemetry TELE; MultipleTelemetry TELE;
AprilTagWebcam webcam; AprilTagWebcam webcam;
@@ -27,6 +29,8 @@ public class Turret {
private double offset = 0.0; private double offset = 0.0;
private double bearing = 0.0; private double bearing = 0.0;
public Turret(Robot rob, MultipleTelemetry tele, AprilTagWebcam cam) { public Turret(Robot rob, MultipleTelemetry tele, AprilTagWebcam cam) {
this.TELE = tele; this.TELE = tele;
this.robot = rob; this.robot = rob;
@@ -85,9 +89,7 @@ public class Turret {
return obeliskID; return obeliskID;
} }
public void update() {
}
/* /*
Param @deltaPos = Pose2d when subtracting robot x, y, heading from goal x, y, heading Param @deltaPos = Pose2d when subtracting robot x, y, heading from goal x, y, heading
@@ -107,15 +109,18 @@ public class Turret {
// Turret angle needed relative to robot // Turret angle needed relative to robot
double turretAngleDeg = desiredTurretAngleDeg - robotHeadingDeg; double turretAngleDeg = desiredTurretAngleDeg - robotHeadingDeg;
turretAngleDeg = -turretAngleDeg;
// Normalize to [-180, 180] // Normalize to [-180, 180]
while (turretAngleDeg > 180) turretAngleDeg -= 360; while (turretAngleDeg > 180) turretAngleDeg -= 360;
while (turretAngleDeg < -180) turretAngleDeg += 360; while (turretAngleDeg < -180) turretAngleDeg += 360;
/* ---------------- APRILTAG CORRECTION ---------------- */
/* ---------------- APRILTAG CORRECTION ---------------- */
//
double tagBearingDeg = getBearing(); // + = target is to the left double tagBearingDeg = getBearing(); // + = target is to the left
if (tagBearingDeg != 1000.0 && Math.abs(tagBearingDeg) < cameraBearingEqual) { if (tagBearingDeg != 1000.0 && Math.abs(tagBearingDeg) > cameraBearingEqual) {
// Slowly learn turret offset (persistent calibration) // Slowly learn turret offset (persistent calibration)
offset -= tagBearingDeg * errorLearningRate; offset -= tagBearingDeg * errorLearningRate;
} }
@@ -124,7 +129,7 @@ public class Turret {
/* ---------------- ANGLE → SERVO ---------------- */ /* ---------------- ANGLE → SERVO ---------------- */
double turretPos = turrDefault + (turretAngleDeg / (turret180Range * 2.0)); double turretPos = turrDefault + (turretAngleDeg * (turret180Range * 2.0) / 360);
// Clamp to servo range // Clamp to servo range
turretPos = Math.max(turrMin, Math.min(turretPos, turrMax)); turretPos = Math.max(turrMin, Math.min(turretPos, turrMax));