Compare commits
21 Commits
SpindexerP
...
4050a354f7
| Author | SHA1 | Date | |
|---|---|---|---|
| 4050a354f7 | |||
| f20e640c62 | |||
| c2e9d8fa87 | |||
| 46a5366a4a | |||
| fbdeb6e291 | |||
|
|
298b7bca8c | ||
| 2f0fcad128 | |||
| 45199b952b | |||
| 76ceb91fb7 | |||
| daccec4fdd | |||
| b55d44ae97 | |||
| 50212015e3 | |||
| c271c88e45 | |||
| 33300876ef | |||
| e1745500cc | |||
| 0dbf155608 | |||
| 313eeeaa95 | |||
| b28647373a | |||
| 7e7254aaea | |||
| a3068cea2e | |||
| f1d4bb9d24 |
@@ -710,7 +710,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
||||
bearing = result.getTx();
|
||||
}
|
||||
}
|
||||
double turretPos = robot.turr1Pos.getCurrentPosition() - (bearing / 1300);
|
||||
double turretPos = (bearing / 1300);
|
||||
robot.turr1.setPosition(turretPos);
|
||||
robot.turr2.setPosition(1 - turretPos);
|
||||
}
|
||||
|
||||
@@ -12,7 +12,7 @@ public class Poses {
|
||||
|
||||
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 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 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);
|
||||
|
||||
}
|
||||
|
||||
@@ -42,4 +42,8 @@ public class ServoPositions {
|
||||
public static double turret_detectBlueClose = 0.6;
|
||||
public static double turrDefault = 0.4;
|
||||
|
||||
public static double turrMin = 0.2;
|
||||
public static double turrMax = 0.8;
|
||||
|
||||
|
||||
}
|
||||
|
||||
@@ -1,11 +1,9 @@
|
||||
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.ServoPositions.spindexer_intakePos1;
|
||||
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.turrDefault;
|
||||
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;
|
||||
@@ -21,7 +19,6 @@ import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
||||
import com.acmerobotics.roadrunner.Vector2d;
|
||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||
import com.qualcomm.hardware.lynx.LynxModule;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
@@ -29,10 +26,13 @@ import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
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.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.ArrayList;
|
||||
import java.util.List;
|
||||
@@ -53,6 +53,8 @@ public class TeleopV3 extends LinearOpMode {
|
||||
public static boolean manualTurret = true;
|
||||
public double vel = 3000;
|
||||
public boolean autoVel = true;
|
||||
public boolean targetingVel = true;
|
||||
public boolean targetingHood = true;
|
||||
public double manualOffset = 0.0;
|
||||
public boolean autoHood = true;
|
||||
public boolean green1 = false;
|
||||
@@ -72,6 +74,8 @@ public class TeleopV3 extends LinearOpMode {
|
||||
Flywheel flywheel;
|
||||
MecanumDrive drive;
|
||||
Spindexer spindexer;
|
||||
Targeting targeting;
|
||||
Targeting.Settings targetingSettings;
|
||||
double autoHoodOffset = 0.0;
|
||||
|
||||
int shooterTicker = 0;
|
||||
@@ -116,6 +120,7 @@ public class TeleopV3 extends LinearOpMode {
|
||||
private double transferStamp = 0.0;
|
||||
private int tickerA = 1;
|
||||
private boolean transferIn = false;
|
||||
boolean turretInterpolate = false;
|
||||
|
||||
public static double velPrediction(double distance) {
|
||||
if (distance < 30) {
|
||||
@@ -146,18 +151,26 @@ public class TeleopV3 extends LinearOpMode {
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||
spindexer = new Spindexer(hardwareMap);
|
||||
targeting = new Targeting();
|
||||
targetingSettings = new Targeting.Settings(0.0, 0.0);
|
||||
|
||||
PIDFController tController = new PIDFController(tp, ti, td, tf);
|
||||
|
||||
tController.setTolerance(0.001);
|
||||
//
|
||||
// if (redAlliance) {
|
||||
// robot.limelight.pipelineSwitch(3);
|
||||
// } else {
|
||||
// robot.limelight.pipelineSwitch(2);
|
||||
// }
|
||||
|
||||
if (redAlliance) {
|
||||
robot.limelight.pipelineSwitch(3);
|
||||
} else {
|
||||
robot.limelight.pipelineSwitch(2);
|
||||
}
|
||||
// robot.limelight.start();
|
||||
|
||||
robot.limelight.start();
|
||||
AprilTagWebcam webcam = new AprilTagWebcam();
|
||||
webcam.init(robot, TELE);
|
||||
|
||||
Turret turret = new Turret(robot, TELE, webcam);
|
||||
waitForStart();
|
||||
|
||||
waitForStart();
|
||||
if (isStopRequested()) return;
|
||||
@@ -372,43 +385,26 @@ public class TeleopV3 extends LinearOpMode {
|
||||
double robotY = robY - yOffset;
|
||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
||||
|
||||
double goalX = -10;
|
||||
double goalX = -15;
|
||||
double goalY = 0;
|
||||
|
||||
double dx = goalX - robotX; // delta x from robot to goal
|
||||
double dy = goalY - robotY; // delta y from robot to goal
|
||||
double dx = robotX - goalX; // delta x 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);
|
||||
|
||||
desiredTurretAngle = (Math.toDegrees(Math.atan2(dy, dx)) + 360) % 360;
|
||||
targetingSettings = targeting.calculateSettings
|
||||
(robotX,robotY,robotHeading,0.0, turretInterpolate);
|
||||
|
||||
desiredTurretAngle += manualOffset + error;
|
||||
turret.trackGoal(deltaPose);
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
//SHOOTER:
|
||||
|
||||
flywheel.manageFlywheel(vel);
|
||||
webcam.update();
|
||||
|
||||
//VELOCITY AUTOMATIC
|
||||
|
||||
if (autoVel) {
|
||||
if (targetingVel) {
|
||||
vel = targetingSettings.flywheelRPM;
|
||||
} else if (autoVel) {
|
||||
vel = velPrediction(distanceToGoal);
|
||||
} else {
|
||||
vel = manualVel;
|
||||
@@ -430,57 +426,39 @@ public class TeleopV3 extends LinearOpMode {
|
||||
manualVel = 3100;
|
||||
}
|
||||
|
||||
//SHOOTER:
|
||||
flywheel.manageFlywheel(vel);
|
||||
|
||||
//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
|
||||
double bearing;
|
||||
|
||||
LLResult result = robot.limelight.getLatestResult();
|
||||
if (result != null) {
|
||||
if (result.isValid()) {
|
||||
bearing = result.getTx() * bMult;
|
||||
|
||||
double bearingCorrection = bearing / bDiv;
|
||||
|
||||
error += bearingCorrection;
|
||||
|
||||
camTicker++;
|
||||
TELE.addData("tx", bearingCorrection);
|
||||
TELE.addData("ty", result.getTy());
|
||||
}
|
||||
}
|
||||
|
||||
} else {
|
||||
camTicker = 0;
|
||||
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);
|
||||
// if (y < 0.3 && y > -0.3 && x < 0.3 && x > -0.3 && rx < 0.3 && rx > -0.3) { //not moving
|
||||
// double bearing;
|
||||
//
|
||||
// LLResult result = robot.light.getLatestResult();
|
||||
// if (result != null) {
|
||||
// if (result.isValid()) {
|
||||
// bearing = result.getTx() * bMult;
|
||||
//
|
||||
// double bearingCorrection = bearing / bDiv;
|
||||
//
|
||||
// error += bearingCorrection;
|
||||
//
|
||||
// camTicker++;
|
||||
// TELE.addData("tx", bearingCorrection);
|
||||
// TELE.addData("ty", result.getTy());
|
||||
// }
|
||||
// }
|
||||
//
|
||||
// } else {
|
||||
// camTicker = 0;
|
||||
// overrideTurr = false;
|
||||
// }
|
||||
|
||||
//HOOD:
|
||||
|
||||
if (autoHood) {
|
||||
if (targetingHood) {
|
||||
robot.hood.setPosition(targetingSettings.hoodAngle);
|
||||
} else if (autoHood) {
|
||||
robot.hood.setPosition(0.15 + hoodOffset);
|
||||
} else {
|
||||
robot.hood.setPosition(hoodDefaultPos + hoodOffset);
|
||||
@@ -845,16 +823,28 @@ public class TeleopV3 extends LinearOpMode {
|
||||
TELE.addData("shootOrder", shootOrder);
|
||||
TELE.addData("oddColor", oddBallColor);
|
||||
|
||||
// Spindexer Debug
|
||||
TELE.addData("spinEqual", servo.spinEqual(spindexer_intakePos1));
|
||||
TELE.addData("spinCommmandedPos", spindexer.commandedIntakePosition);
|
||||
TELE.addData("spinIntakeState", spindexer.currentIntakeState);
|
||||
TELE.addData("spinTestCounter", spindexer.counter);
|
||||
TELE.addData("autoSpintake", autoSpintake);
|
||||
TELE.addData("distanceRearCenter", spindexer.distanceRearCenter);
|
||||
TELE.addData("distanceFrontDriver", spindexer.distanceFrontDriver);
|
||||
TELE.addData("distanceFrontPassenger", spindexer.distanceFrontPassenger);
|
||||
//TELE.addData("distanceRearCenter", spindexer.distanceRearCenter);
|
||||
//TELE.addData("distanceFrontDriver", spindexer.distanceFrontDriver);
|
||||
//TELE.addData("distanceFrontPassenger", spindexer.distanceFrontPassenger);
|
||||
TELE.addData("shootall commanded", shootAll);
|
||||
// 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("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.update();
|
||||
|
||||
ticker++;
|
||||
|
||||
@@ -52,7 +52,6 @@ public class PIDServoTest extends LinearOpMode {
|
||||
}
|
||||
|
||||
telemetry.addData("pos", pos);
|
||||
telemetry.addData("Turret Voltage", robot.turr1Pos.getCurrentPosition());
|
||||
telemetry.addData("Spindex Voltage", robot.spin1Pos.getVoltage());
|
||||
telemetry.addData("target", target);
|
||||
telemetry.addData("Mode", mode);
|
||||
|
||||
@@ -0,0 +1,50 @@
|
||||
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.Pose2d;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
||||
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||
|
||||
@Autonomous
|
||||
@Config
|
||||
public class TurretTest extends LinearOpMode {
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
Robot robot = new Robot(hardwareMap);
|
||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
);
|
||||
|
||||
AprilTagWebcam webcam = new AprilTagWebcam();
|
||||
webcam.init(robot, TELE);
|
||||
|
||||
Turret turret = new Turret(robot, TELE, webcam);
|
||||
waitForStart();
|
||||
|
||||
|
||||
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(15, 0,0));
|
||||
|
||||
while(opModeIsActive()){
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
turret.trackGoal(drive.localizer.getPose());
|
||||
|
||||
webcam.update();
|
||||
webcam.displayAllTelemetry();
|
||||
|
||||
|
||||
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
@@ -1,22 +1,13 @@
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.kP;
|
||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.maxStep;
|
||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
|
||||
|
||||
public class Flywheel {
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
|
||||
double initPos = 0.0;
|
||||
double stamp = 0.0;
|
||||
double stamp1 = 0.0;
|
||||
double ticker = 0.0;
|
||||
double currentPos = 0.0;
|
||||
public PIDFCoefficients shooterPIDF1, shooterPIDF2;
|
||||
double velo = 0.0;
|
||||
double velo1 = 0.0;
|
||||
double velo2 = 0.0;
|
||||
@@ -25,6 +16,10 @@ public class Flywheel {
|
||||
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);
|
||||
shooterPIDF2 = new PIDFCoefficients
|
||||
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
|
||||
}
|
||||
|
||||
public double getVelo () {
|
||||
@@ -48,10 +43,6 @@ public class Flywheel {
|
||||
robot.shooterPIDF.d = d;
|
||||
robot.shooterPIDF.f = f;
|
||||
}
|
||||
private double getTimeSeconds ()
|
||||
{
|
||||
return (double) System.currentTimeMillis()/1000.0;
|
||||
}
|
||||
|
||||
// Convert from RPM to Ticks per Second
|
||||
private double RPM_to_TPS (double RPM) { return (RPM*28.0)/60.0;}
|
||||
@@ -62,19 +53,20 @@ public class Flywheel {
|
||||
public double manageFlywheel(double commandedVelocity) {
|
||||
targetVelocity = commandedVelocity;
|
||||
|
||||
// Turn PIDF for Target Velocities
|
||||
// Add code here to set PIDF based on desired RPM
|
||||
//robot.shooterPIDF.p = P;
|
||||
//robot.shooterPIDF.i = I;
|
||||
//robot.shooterPIDF.d = D;
|
||||
//robot.shooterPIDF.f = F;
|
||||
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, robot.shooterPIDF);
|
||||
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, robot.shooterPIDF);
|
||||
|
||||
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.shooter1.getVelocity()); // Possible error: should it be shooter2 not shooter1?
|
||||
velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
|
||||
velo = Math.max(velo1,velo2);
|
||||
|
||||
// really should be a running average of the last 5
|
||||
|
||||
@@ -71,7 +71,6 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
||||
TELE.addData("spindexer voltage 2", robot.spin2Pos.getVoltage());
|
||||
TELE.addData("hood pos", robot.hood.getPosition());
|
||||
TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage());
|
||||
TELE.addData("turret voltage", robot.turr1Pos.getCurrentPosition());
|
||||
TELE.addData("spindexer pow", robot.spin1.getPower());
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
@@ -1,5 +1,6 @@
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||
import com.qualcomm.hardware.rev.RevColorSensorV3;
|
||||
import com.qualcomm.robotcore.hardware.AnalogInput;
|
||||
@@ -14,10 +15,13 @@ import com.qualcomm.robotcore.hardware.Servo;
|
||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
|
||||
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
|
||||
|
||||
@Config
|
||||
public class Robot {
|
||||
|
||||
//Initialize Public Components
|
||||
|
||||
public static boolean usingLimelight = false;
|
||||
public static boolean usingCamera = true;
|
||||
public DcMotorEx frontLeft;
|
||||
public DcMotorEx frontRight;
|
||||
public DcMotorEx backLeft;
|
||||
@@ -29,8 +33,7 @@ public class Robot {
|
||||
public double shooterPIDF_I = 0.6;
|
||||
public double shooterPIDF_D = 5.0;
|
||||
public double shooterPIDF_F = 10.0;
|
||||
|
||||
public double[] shooterPIDF_StepSizes = {10.0,1.0,0.001, 0.0001};
|
||||
public double[] shooterPIDF_StepSizes = {10.0, 1.0, 0.001, 0.0001};
|
||||
public DcMotorEx shooter1;
|
||||
public DcMotorEx shooter2;
|
||||
public Servo hood;
|
||||
@@ -41,7 +44,7 @@ public class Robot {
|
||||
public CRServo spin2;
|
||||
public AnalogInput spin1Pos;
|
||||
public AnalogInput spin2Pos;
|
||||
public DcMotorEx turr1Pos;
|
||||
public AnalogInput turr1Pos;
|
||||
public AnalogInput transferServoPos;
|
||||
public AprilTagProcessor aprilTagProcessor;
|
||||
public WebcamName webcam;
|
||||
@@ -50,10 +53,6 @@ public class Robot {
|
||||
public RevColorSensorV3 color3;
|
||||
public Limelight3A limelight;
|
||||
|
||||
public static boolean usingLimelight = true;
|
||||
|
||||
public static boolean usingCamera = true;
|
||||
|
||||
public Robot(HardwareMap hardwareMap) {
|
||||
|
||||
//Define components w/ hardware map
|
||||
@@ -77,11 +76,13 @@ public class Robot {
|
||||
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
|
||||
//TODO: figure out which shooter motor is reversed using ShooterTest and change it in code @KeshavAnandCode
|
||||
shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
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.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
||||
shooter1.setVelocity(1400);
|
||||
shooter2.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
||||
shooter2.setVelocity(1400);
|
||||
|
||||
hood = hardwareMap.get(Servo.class, "hood");
|
||||
|
||||
@@ -89,7 +90,7 @@ public class Robot {
|
||||
|
||||
turr2 = hardwareMap.get(Servo.class, "t2");
|
||||
|
||||
turr1Pos = intake; // Encoder of turret plugged in intake port
|
||||
turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // Encoder of turret plugged in intake port
|
||||
|
||||
//TODO: check spindexer configuration (both servo and analog input) - check comments in PositionalServoProgrammer
|
||||
spin1 = hardwareMap.get(CRServo.class, "spin1");
|
||||
@@ -118,9 +119,9 @@ public class Robot {
|
||||
|
||||
color3 = hardwareMap.get(RevColorSensorV3.class, "c3");
|
||||
|
||||
if (usingLimelight){
|
||||
if (usingLimelight) {
|
||||
limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
||||
} else if (usingCamera){
|
||||
} else if (usingCamera) {
|
||||
webcam = hardwareMap.get(WebcamName.class, "Webcam 1");
|
||||
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
|
||||
}
|
||||
|
||||
@@ -44,17 +44,15 @@ public class Servos {
|
||||
}
|
||||
|
||||
public double getTurrPos() {
|
||||
return (double) ((double) robot.turr1Pos.getCurrentPosition() / 1024.0) * ((double) 44.0 / (double) 77.0);
|
||||
return 1.0;
|
||||
|
||||
}
|
||||
|
||||
public double setTurrPos(double pos) {
|
||||
turretPID.setPIDF(turrP, turrI, turrD, turrF);
|
||||
|
||||
return spinPID.calculate(this.getTurrPos(), pos);
|
||||
return 1.0;
|
||||
}
|
||||
|
||||
public boolean turretEqual(double pos) {
|
||||
return Math.abs(pos - this.getTurrPos()) < 0.01;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -52,7 +52,9 @@ public class Spindexer {
|
||||
}
|
||||
|
||||
enum IntakeState {
|
||||
UNKNOWN,
|
||||
UNKNOWN_START,
|
||||
UNKNOWN_MOVE,
|
||||
UNKNOWN_DETECT,
|
||||
INTAKE,
|
||||
FINDNEXT,
|
||||
MOVING,
|
||||
@@ -62,8 +64,8 @@ public class Spindexer {
|
||||
SHOOTWAIT,
|
||||
};
|
||||
|
||||
public IntakeState currentIntakeState = IntakeState.UNKNOWN;
|
||||
|
||||
public IntakeState currentIntakeState = IntakeState.UNKNOWN_START;
|
||||
public int unknownColorDetect = 0;
|
||||
enum BallColor {
|
||||
UNKNOWN,
|
||||
GREEN,
|
||||
@@ -131,13 +133,13 @@ public class Spindexer {
|
||||
for (int i = 0; i < 3; i++) {
|
||||
resetBallPosition(i);
|
||||
}
|
||||
currentIntakeState = IntakeState.UNKNOWN;
|
||||
currentIntakeState = IntakeState.UNKNOWN_START;
|
||||
}
|
||||
|
||||
// Detects if a ball is found and what color.
|
||||
// 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.
|
||||
public boolean detectBalls() {
|
||||
public boolean detectBalls(boolean detectRearColor, boolean detectFrontColor) {
|
||||
|
||||
boolean newPos1Detection = false;
|
||||
int spindexerBallPos = 0;
|
||||
@@ -153,18 +155,20 @@ public class Spindexer {
|
||||
// Mark Ball Found
|
||||
newPos1Detection = true;
|
||||
|
||||
// Detect which color
|
||||
double green = robot.color1.getNormalizedColors().green;
|
||||
double red = robot.color1.getNormalizedColors().red;
|
||||
double blue = robot.color1.getNormalizedColors().blue;
|
||||
if (detectRearColor) {
|
||||
// Detect which color
|
||||
double green = robot.color1.getNormalizedColors().green;
|
||||
double red = robot.color1.getNormalizedColors().red;
|
||||
double blue = robot.color1.getNormalizedColors().blue;
|
||||
|
||||
double gP = green / (green + red + blue);
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
// FIXIT - Add filtering to improve accuracy.
|
||||
if (gP >= 0.4) {
|
||||
ballPositions[commandedIntakePosition].ballColor = BallColor.PURPLE; // purple
|
||||
} else {
|
||||
ballPositions[commandedIntakePosition].ballColor = BallColor.GREEN; // purple
|
||||
// FIXIT - Add filtering to improve accuracy.
|
||||
if (gP >= 0.4) {
|
||||
ballPositions[commandedIntakePosition].ballColor = BallColor.PURPLE; // purple
|
||||
} else {
|
||||
ballPositions[commandedIntakePosition].ballColor = BallColor.GREEN; // purple
|
||||
}
|
||||
}
|
||||
}
|
||||
// Position 2
|
||||
@@ -173,18 +177,19 @@ public class Spindexer {
|
||||
if (distanceFrontDriver < 60) {
|
||||
// reset FoundEmpty because looking for 3 in a row before reset
|
||||
ballPositions[spindexerBallPos].foundEmpty = 0;
|
||||
// FIXIT: Comment out for now due to loop time concerns
|
||||
// double green = robot.color2.getNormalizedColors().green;
|
||||
// double red = robot.color2.getNormalizedColors().red;
|
||||
// double blue = robot.color2.getNormalizedColors().blue;
|
||||
//
|
||||
// double gP = green / (green + red + blue);
|
||||
if (detectFrontColor) {
|
||||
double green = robot.color2.getNormalizedColors().green;
|
||||
double red = robot.color2.getNormalizedColors().red;
|
||||
double blue = robot.color2.getNormalizedColors().blue;
|
||||
|
||||
// if (gP >= 0.4) {
|
||||
// b2 = 2; // purple
|
||||
// } else {
|
||||
// b2 = 1; // green
|
||||
// }
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
if (gP >= 0.4) {
|
||||
ballPositions[spindexerBallPos].ballColor = BallColor.PURPLE; // purple
|
||||
} else {
|
||||
ballPositions[spindexerBallPos].ballColor = BallColor.GREEN; // purple
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if (!ballPositions[spindexerBallPos].isEmpty) {
|
||||
if (ballPositions[spindexerBallPos].foundEmpty > 3) {
|
||||
@@ -201,18 +206,19 @@ public class Spindexer {
|
||||
|
||||
// reset FoundEmpty because looking for 3 in a row before reset
|
||||
ballPositions[spindexerBallPos].foundEmpty = 0;
|
||||
// FIXIT: Comment out for now due to loop time concerns
|
||||
// double green = robot.color3.getNormalizedColors().green;
|
||||
// double red = robot.color3.getNormalizedColors().red;
|
||||
// double blue = robot.color3.getNormalizedColors().blue;
|
||||
if (detectFrontColor) {
|
||||
double green = robot.color3.getNormalizedColors().green;
|
||||
double red = robot.color3.getNormalizedColors().red;
|
||||
double blue = robot.color3.getNormalizedColors().blue;
|
||||
|
||||
// double gP = green / (green + red + blue);
|
||||
double gP = green / (green + red + blue);
|
||||
|
||||
// if (gP >= 0.4) {
|
||||
// b3 = 2; // purple
|
||||
// } else {
|
||||
// b3 = 1; // green
|
||||
// }
|
||||
if (gP >= 0.4) {
|
||||
ballPositions[spindexerBallPos].ballColor = BallColor.PURPLE; // purple
|
||||
} else {
|
||||
ballPositions[spindexerBallPos].ballColor = BallColor.GREEN; // purple
|
||||
}
|
||||
}
|
||||
} else {
|
||||
if (!ballPositions[spindexerBallPos].isEmpty) {
|
||||
if (ballPositions[spindexerBallPos].foundEmpty > 3) {
|
||||
@@ -255,15 +261,35 @@ public class Spindexer {
|
||||
public boolean processIntake() {
|
||||
|
||||
switch (currentIntakeState) {
|
||||
case UNKNOWN:
|
||||
case UNKNOWN_START:
|
||||
// For now just set position ONE if UNKNOWN
|
||||
commandedIntakePosition = 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;
|
||||
case INTAKE:
|
||||
// Ready for intake and Detecting a New Ball
|
||||
if (detectBalls()) {
|
||||
if (detectBalls(true, false)) {
|
||||
ballPositions[commandedIntakePosition].isEmpty = false;
|
||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||
} else {
|
||||
@@ -311,7 +337,7 @@ public class Spindexer {
|
||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.INTAKE;
|
||||
stopSpindexer();
|
||||
detectBalls();
|
||||
detectBalls(false, false);
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
@@ -320,7 +346,7 @@ public class Spindexer {
|
||||
|
||||
case FULL:
|
||||
// Double Check Colors
|
||||
detectBalls();
|
||||
detectBalls(false, false); // Minimize hardware calls
|
||||
if (ballPositions[0].isEmpty || ballPositions[1].isEmpty || ballPositions[2].isEmpty) {
|
||||
// Error handling found an empty spot, get it ready for a ball
|
||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||
@@ -378,7 +404,7 @@ public class Spindexer {
|
||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.INTAKE;
|
||||
stopSpindexer();
|
||||
detectBalls();
|
||||
detectBalls(true, false);
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
|
||||
@@ -0,0 +1,141 @@
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import android.provider.Settings;
|
||||
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
|
||||
public class Targeting {
|
||||
MultipleTelemetry TELE;
|
||||
|
||||
double cancelOffsetX = 7.071067811;
|
||||
double cancelOffsetY = 7.071067811;
|
||||
double unitConversionFactor = 0.95;
|
||||
|
||||
int tileSize = 24; //inches
|
||||
|
||||
public double robotInchesX, robotInchesY = 0.0;
|
||||
|
||||
public int robotGridX, robotGridY = 0;
|
||||
|
||||
|
||||
public static class Settings {
|
||||
public double flywheelRPM = 0.0;
|
||||
public double hoodAngle = 0.0;
|
||||
|
||||
public Settings (double flywheelRPM, double hoodAngle) {
|
||||
this.flywheelRPM = flywheelRPM;
|
||||
this.hoodAngle = hoodAngle;
|
||||
}
|
||||
}
|
||||
|
||||
// Known settings discovered using shooter test.
|
||||
// Keep the fidelity at 1 floor tile for now but we could also half it if more
|
||||
// accuracy is needed.
|
||||
public static final Settings[][] KNOWNTARGETING;
|
||||
static {
|
||||
KNOWNTARGETING = new Settings[6][6];
|
||||
// ROW 0 - Closet to the goals
|
||||
KNOWNTARGETING[0][0] = new Settings (3000.0, 0.25);
|
||||
KNOWNTARGETING[0][1] = new Settings (3001.0, 0.25);
|
||||
KNOWNTARGETING[0][2] = new Settings (3002.0, 0.25);
|
||||
KNOWNTARGETING[0][3] = new Settings (3302.0, 0.2);
|
||||
KNOWNTARGETING[0][4] = new Settings (3503.0, 0.15);
|
||||
KNOWNTARGETING[0][5] = new Settings (3505.0, 0.15);
|
||||
// ROW 1
|
||||
KNOWNTARGETING[1][0] = new Settings (3010.0, 0.25);
|
||||
KNOWNTARGETING[1][1] = new Settings (3011.0, 0.25);
|
||||
KNOWNTARGETING[1][2] = new Settings (3012.0, 0.25);
|
||||
KNOWNTARGETING[1][3] = new Settings (3313.0, 0.15);
|
||||
KNOWNTARGETING[1][4] = new Settings (3514.0, 0.15);
|
||||
KNOWNTARGETING[1][5] = new Settings (3515.0, 0.15);
|
||||
// ROW 2
|
||||
KNOWNTARGETING[2][0] = new Settings (3020.0, 0.1);
|
||||
KNOWNTARGETING[2][1] = new Settings (3000.0, 0.25);
|
||||
KNOWNTARGETING[2][2] = new Settings (3000.0, 0.15);
|
||||
KNOWNTARGETING[2][3] = new Settings (3000.0, 0.15);
|
||||
KNOWNTARGETING[2][4] = new Settings (3524.0, 0.15);
|
||||
KNOWNTARGETING[2][5] = new Settings (3525.0, 0.15);
|
||||
// ROW 3
|
||||
KNOWNTARGETING[3][0] = new Settings (3030.0, 0.15);
|
||||
KNOWNTARGETING[3][1] = new Settings (3031.0, 0.15);
|
||||
KNOWNTARGETING[3][2] = new Settings (3000.0, 0.15);
|
||||
KNOWNTARGETING[3][3] = new Settings (3000.0, 0.15);
|
||||
KNOWNTARGETING[3][4] = new Settings (3000.0, 0.03);
|
||||
KNOWNTARGETING[3][5] = new Settings (3535.0, 0.1);
|
||||
// ROW 4
|
||||
KNOWNTARGETING[4][0] = new Settings (4540.0, 0.1);
|
||||
KNOWNTARGETING[4][1] = new Settings (4541.0, 0.1);
|
||||
KNOWNTARGETING[4][2] = new Settings (4542.0, 0.1);
|
||||
KNOWNTARGETING[4][3] = new Settings (4543.0, 0.1);
|
||||
KNOWNTARGETING[4][4] = new Settings (4544.0, 0.1);
|
||||
KNOWNTARGETING[4][5] = new Settings (4545.0, 0.1);
|
||||
// ROW 1
|
||||
KNOWNTARGETING[5][0] = new Settings (4550.0, 0.1);
|
||||
KNOWNTARGETING[5][1] = new Settings (4551.0, 0.1);
|
||||
KNOWNTARGETING[5][2] = new Settings (4552.0, 0.1);
|
||||
KNOWNTARGETING[5][3] = new Settings (4553.0, 0.1);
|
||||
KNOWNTARGETING[5][4] = new Settings (4554.0, 0.1);
|
||||
KNOWNTARGETING[5][5] = new Settings (4555.0, 0.1);
|
||||
}
|
||||
|
||||
public Targeting()
|
||||
{
|
||||
}
|
||||
|
||||
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 - 40.0) * sin45 + (robotY + 7.0) * cos45;
|
||||
double rotatedX = (robotX - 40.0) * cos45 - (robotY + 7.0) * sin45;
|
||||
|
||||
// Convert robot coordinates to inches
|
||||
robotInchesX = rotatedX * unitConversionFactor;
|
||||
robotInchesY = rotatedY * unitConversionFactor;
|
||||
|
||||
// Find approximate location in the grid
|
||||
int gridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) + 1);
|
||||
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
|
||||
|
||||
//clamp
|
||||
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)) {
|
||||
recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridY][robotGridX].flywheelRPM;
|
||||
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridY][robotGridX].hoodAngle;
|
||||
}
|
||||
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;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,147 @@
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
|
||||
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||
|
||||
@Config
|
||||
public class Turret {
|
||||
|
||||
public static double turretTolerance = 0.02;
|
||||
public static double turrPosScalar = 1.009;
|
||||
public static double turret180Range = 0.4;
|
||||
public static double turrDefault = 0.4;
|
||||
public static double cameraBearingEqual = 1;
|
||||
public static double errorLearningRate = 0.15;
|
||||
public static double turrMin = 0.2;
|
||||
public static double turrMax = 0.8;
|
||||
public static double deltaAngleThreshold = 0.02;
|
||||
public static double angleMultiplier = 0.0;
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
AprilTagWebcam webcam;
|
||||
private int obeliskID = 0;
|
||||
private double turrPos = 0.0;
|
||||
private double offset = 0.0;
|
||||
private double bearing = 0.0;
|
||||
|
||||
|
||||
|
||||
public Turret(Robot rob, MultipleTelemetry tele, AprilTagWebcam cam) {
|
||||
this.TELE = tele;
|
||||
this.robot = rob;
|
||||
this.webcam = cam;
|
||||
}
|
||||
|
||||
public double getTurrPos() {
|
||||
return turrPosScalar * (robot.turr1Pos.getVoltage() / 3.3);
|
||||
|
||||
}
|
||||
|
||||
public void manualSetTurret(double pos){
|
||||
robot.turr1.setPosition(pos);
|
||||
robot.turr2.setPosition(1-pos);
|
||||
}
|
||||
|
||||
public boolean turretEqual(double pos) {
|
||||
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
|
||||
}
|
||||
|
||||
public double getBearing() {
|
||||
if (redAlliance) {
|
||||
AprilTagDetection d24 = webcam.getTagById(24);
|
||||
if (d24 != null) {
|
||||
bearing = d24.ftcPose.bearing;
|
||||
return bearing;
|
||||
} else {
|
||||
return 1000.0;
|
||||
}
|
||||
} else {
|
||||
AprilTagDetection d20 = webcam.getTagById(20);
|
||||
if (d20 != null) {
|
||||
bearing = d20.ftcPose.bearing;
|
||||
return bearing;
|
||||
} else {
|
||||
return 1000.0;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public int detectObelisk() {
|
||||
AprilTagDetection id21 = webcam.getTagById(21);
|
||||
AprilTagDetection id22 = webcam.getTagById(22);
|
||||
AprilTagDetection id23 = webcam.getTagById(23);
|
||||
if (id21 != null) {
|
||||
obeliskID = 21;
|
||||
} else if (id22 != null) {
|
||||
obeliskID = 22;
|
||||
} else if (id23 != null) {
|
||||
obeliskID = 23;
|
||||
}
|
||||
return obeliskID;
|
||||
}
|
||||
|
||||
public int getObeliskID() {
|
||||
return obeliskID;
|
||||
}
|
||||
|
||||
|
||||
|
||||
/*
|
||||
Param @deltaPos = Pose2d when subtracting robot x, y, heading from goal x, y, heading
|
||||
*/
|
||||
public void trackGoal(Pose2d deltaPos) {
|
||||
|
||||
/* ---------------- FIELD → TURRET GEOMETRY ---------------- */
|
||||
|
||||
// Angle from robot to goal in robot frame
|
||||
double desiredTurretAngleDeg = Math.toDegrees(
|
||||
Math.atan2(deltaPos.position.y, deltaPos.position.x)
|
||||
);
|
||||
|
||||
// Robot heading (field → robot)
|
||||
double robotHeadingDeg = Math.toDegrees(deltaPos.heading.toDouble());
|
||||
|
||||
// Turret angle needed relative to robot
|
||||
double turretAngleDeg = desiredTurretAngleDeg - robotHeadingDeg;
|
||||
|
||||
turretAngleDeg = -turretAngleDeg;
|
||||
|
||||
// Normalize to [-180, 180]
|
||||
while (turretAngleDeg > 180) turretAngleDeg -= 360;
|
||||
while (turretAngleDeg < -180) turretAngleDeg += 360;
|
||||
|
||||
|
||||
/* ---------------- APRILTAG CORRECTION ---------------- */
|
||||
//
|
||||
double tagBearingDeg = getBearing(); // + = target is to the left
|
||||
|
||||
if (tagBearingDeg != 1000.0 && Math.abs(tagBearingDeg) > cameraBearingEqual) {
|
||||
// Slowly learn turret offset (persistent calibration)
|
||||
offset -= tagBearingDeg * errorLearningRate;
|
||||
}
|
||||
|
||||
turretAngleDeg += offset;
|
||||
|
||||
/* ---------------- ANGLE → SERVO ---------------- */
|
||||
|
||||
double turretPos = turrDefault + (turretAngleDeg * (turret180Range * 2.0) / 360);
|
||||
|
||||
// Clamp to servo range
|
||||
turretPos = Math.max(turrMin, Math.min(turretPos, turrMax));
|
||||
|
||||
robot.turr1.setPosition(turretPos);
|
||||
robot.turr2.setPosition(1.0 - turretPos);
|
||||
|
||||
/* ---------------- TELEMETRY ---------------- */
|
||||
|
||||
TELE.addData("Turret Angle", turretAngleDeg);
|
||||
TELE.addData("Bearing", tagBearingDeg);
|
||||
TELE.addData("Offset", offset);
|
||||
}
|
||||
|
||||
}
|
||||
Reference in New Issue
Block a user