Merge with LimelightTesting.
This commit is contained in:
@@ -19,6 +19,7 @@ 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.Limelight3A;
|
||||||
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;
|
||||||
@@ -26,7 +27,6 @@ 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;
|
||||||
@@ -396,8 +396,6 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
turret.trackGoal(deltaPose);
|
turret.trackGoal(deltaPose);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
//VELOCITY AUTOMATIC
|
//VELOCITY AUTOMATIC
|
||||||
if (targetingVel) {
|
if (targetingVel) {
|
||||||
vel = targetingSettings.flywheelRPM;
|
vel = targetingSettings.flywheelRPM;
|
||||||
@@ -634,7 +632,6 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
//
|
//
|
||||||
// if (shootAll) {
|
// if (shootAll) {
|
||||||
//
|
//
|
||||||
@@ -806,7 +803,6 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
for (LynxModule hub : allHubs) {
|
for (LynxModule hub : allHubs) {
|
||||||
hub.clearBulkCache();
|
hub.clearBulkCache();
|
||||||
}
|
}
|
||||||
|
|
||||||
//
|
//
|
||||||
TELE.addData("Spin1Green", green1 + ": " + ballIn(1));
|
TELE.addData("Spin1Green", green1 + ": " + ballIn(1));
|
||||||
TELE.addData("Spin2Green", green2 + ": " + ballIn(2));
|
TELE.addData("Spin2Green", green2 + ": " + ballIn(2));
|
||||||
@@ -833,7 +829,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
TELE.addData("shootall commanded", shootAll);
|
TELE.addData("shootall commanded", shootAll);
|
||||||
// Targeting Debug
|
// Targeting Debug
|
||||||
TELE.addData("robotX", robotX);
|
TELE.addData("robotX", robotX);
|
||||||
TELE.addData( "robotY", robotY);
|
TELE.addData("robotY", robotY);
|
||||||
TELE.addData("robotInchesX", targeting.robotInchesX);
|
TELE.addData("robotInchesX", targeting.robotInchesX);
|
||||||
TELE.addData( "robotInchesY", targeting.robotInchesY);
|
TELE.addData( "robotInchesY", targeting.robotInchesY);
|
||||||
TELE.addData("Targeting Interpolate", turretInterpolate);
|
TELE.addData("Targeting Interpolate", turretInterpolate);
|
||||||
|
|||||||
@@ -4,32 +4,35 @@ import com.acmerobotics.dashboard.FtcDashboard;
|
|||||||
import com.acmerobotics.dashboard.config.Config;
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
|
||||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
|
|
||||||
import java.util.List;
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Turret;
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
@TeleOp
|
@TeleOp
|
||||||
//TODO: fix to get the apriltag that it is reading
|
//TODO: fix to get the apriltag that it is reading
|
||||||
public class LimelightTest extends LinearOpMode {
|
public class LimelightTest extends LinearOpMode {
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
|
Turret turret;
|
||||||
|
Robot robot;
|
||||||
public static int pipeline = 0; //0 is for test; 1 for obelisk; 2 is for blue track; 3 is for red track
|
public static int pipeline = 0; //0 is for test; 1 for obelisk; 2 is for blue track; 3 is for red track
|
||||||
public static int mode = 0; //0 for bare testing, 1 for obelisk, 2 for blue track, 3 for red track
|
public static int mode = 0; //0 for bare testing, 1 for obelisk, 2 for blue track, 3 for red track
|
||||||
|
public static boolean turretMode = false;
|
||||||
|
public static double turretPos = 0.501;
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
Limelight3A limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
|
||||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
limelight.pipelineSwitch(pipeline);
|
robot = new Robot(hardwareMap);
|
||||||
|
turret = new Turret(robot, TELE, robot.limelight);
|
||||||
|
robot.limelight.pipelineSwitch(pipeline);
|
||||||
waitForStart();
|
waitForStart();
|
||||||
if (isStopRequested()) return;
|
if (isStopRequested()) return;
|
||||||
limelight.start();
|
|
||||||
while (opModeIsActive()){
|
while (opModeIsActive()){
|
||||||
if (mode == 0){
|
if (mode == 0){
|
||||||
limelight.pipelineSwitch(pipeline);
|
robot.limelight.pipelineSwitch(pipeline);
|
||||||
LLResult result = limelight.getLatestResult();
|
LLResult result = robot.limelight.getLatestResult();
|
||||||
if (result != null) {
|
if (result != null) {
|
||||||
if (result.isValid()) {
|
if (result.isValid()) {
|
||||||
TELE.addData("tx", result.getTx());
|
TELE.addData("tx", result.getTx());
|
||||||
@@ -38,40 +41,29 @@ public class LimelightTest extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
} else if (mode == 1){
|
} else if (mode == 1){
|
||||||
limelight.pipelineSwitch(1);
|
int obeliskID = turret.detectObelisk();
|
||||||
LLResult result = limelight.getLatestResult();
|
TELE.addData("Limelight ID", obeliskID);
|
||||||
if (result != null && result.isValid()) {
|
|
||||||
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
|
||||||
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
|
||||||
int id = fiducial.getFiducialId();
|
|
||||||
TELE.addData("ID", id);
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
} else if (mode == 2 || mode == 3){ // Use redAlliance variable to switch between red and blue
|
||||||
|
double tx = turret.getBearing();
|
||||||
|
double ty = turret.getTy();
|
||||||
|
double x = turret.getLimelightX();
|
||||||
|
double y = turret.getLimelightY();
|
||||||
|
TELE.addData("tx", tx);
|
||||||
|
TELE.addData("ty", ty);
|
||||||
|
TELE.addData("x", x);
|
||||||
|
TELE.addData("y", y);
|
||||||
|
TELE.update();
|
||||||
|
} else {
|
||||||
|
robot.limelight.pipelineSwitch(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (turretMode){
|
||||||
|
if (turretPos != 0.501){
|
||||||
|
turret.manualSetTurret(turretPos);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
} else if (mode == 2){
|
|
||||||
limelight.pipelineSwitch(4);
|
|
||||||
LLResult result = limelight.getLatestResult();
|
|
||||||
if (result != null) {
|
|
||||||
if (result.isValid()) {
|
|
||||||
TELE.addData("tx", result.getTx());
|
|
||||||
TELE.addData("ty", result.getTy());
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
} else if (mode == 3){
|
|
||||||
limelight.pipelineSwitch(5);
|
|
||||||
LLResult result = limelight.getLatestResult();
|
|
||||||
if (result != null) {
|
|
||||||
if (result.isValid()) {
|
|
||||||
TELE.addData("tx", result.getTx());
|
|
||||||
TELE.addData("ty", result.getTy());
|
|
||||||
TELE.update();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
limelight.pipelineSwitch(0);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -8,15 +8,12 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
|||||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
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.Robot;
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
import org.firstinspires.ftc.teamcode.utils.Turret;
|
||||||
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
|
||||||
|
|
||||||
@Autonomous
|
@Autonomous
|
||||||
@Config
|
@Config
|
||||||
public class TurretTest extends LinearOpMode {
|
public class TurretTest extends LinearOpMode {
|
||||||
|
|
||||||
public static boolean zeroTurr = false;
|
public static boolean zeroTurr = false;
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
@@ -26,11 +23,9 @@ public class TurretTest extends LinearOpMode {
|
|||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
);
|
);
|
||||||
|
|
||||||
|
|
||||||
Turret turret = new Turret(robot, TELE, robot.limelight);
|
Turret turret = new Turret(robot, TELE, robot.limelight);
|
||||||
waitForStart();
|
waitForStart();
|
||||||
|
|
||||||
|
|
||||||
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(15, 0,0));
|
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(15, 0,0));
|
||||||
|
|
||||||
while(opModeIsActive()){
|
while(opModeIsActive()){
|
||||||
@@ -38,16 +33,16 @@ public class TurretTest extends LinearOpMode {
|
|||||||
drive.updatePoseEstimate();
|
drive.updatePoseEstimate();
|
||||||
turret.trackGoal(drive.localizer.getPose());
|
turret.trackGoal(drive.localizer.getPose());
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
TELE.addData("tpos", turret.getTurrPos());
|
TELE.addData("tpos", turret.getTurrPos());
|
||||||
|
TELE.addData("Limelight tx", turret.getBearing());
|
||||||
|
TELE.addData("Limelight ty", turret.getTy());
|
||||||
|
TELE.addData("Limelight X", turret.getLimelightX());
|
||||||
|
TELE.addData("Limelight Y", turret.getLimelightY());
|
||||||
|
|
||||||
if(zeroTurr){
|
if(zeroTurr){
|
||||||
turret.zeroTurretEncoder();
|
turret.zeroTurretEncoder();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -21,7 +21,7 @@ public class Robot {
|
|||||||
//Initialize Public Components
|
//Initialize Public Components
|
||||||
|
|
||||||
public static boolean usingLimelight = true;
|
public static boolean usingLimelight = true;
|
||||||
public static boolean usingCamera = false;
|
public static boolean usingCamera = true;
|
||||||
public DcMotorEx frontLeft;
|
public DcMotorEx frontLeft;
|
||||||
public DcMotorEx frontRight;
|
public DcMotorEx frontRight;
|
||||||
public DcMotorEx backLeft;
|
public DcMotorEx backLeft;
|
||||||
|
|||||||
@@ -1,3 +1,4 @@
|
|||||||
|
|
||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||||
@@ -5,6 +6,7 @@ import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
|||||||
import com.acmerobotics.dashboard.config.Config;
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
import com.acmerobotics.roadrunner.Pose2d;
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||||
@@ -16,52 +18,50 @@ import java.util.List;
|
|||||||
|
|
||||||
@Config
|
@Config
|
||||||
public class Turret {
|
public class Turret {
|
||||||
|
|
||||||
public static double turretTolerance = 0.02;
|
public static double turretTolerance = 0.02;
|
||||||
public static double turrPosScalar = 0.00011264432;
|
public static double turrPosScalar = 0.00011264432;
|
||||||
public static double turret180Range = 0.4;
|
public static double turret180Range = 0.4;
|
||||||
public static double turrDefault = 0.4;
|
public static double turrDefault = 0.4;
|
||||||
|
// TODO: tune these values for limelight
|
||||||
|
// At the top with other static variables:
|
||||||
|
public static double kP = 0.015; // Proportional gain - tune this first
|
||||||
|
public static double kI = 0.0005; // Integral gain - add slowly if needed
|
||||||
|
public static double kD = 0.002; // Derivative gain - helps prevent overshoot
|
||||||
|
|
||||||
|
public static double kF = 0.002; // Derivative gain - helps prevent overshoot
|
||||||
|
|
||||||
|
public static double maxOffset = 10; // degrees - safety limit
|
||||||
|
|
||||||
|
// Add these as instance variables:
|
||||||
|
private double lastTagBearing = 0.0;
|
||||||
|
private double offsetIntegral = 0.0;
|
||||||
|
|
||||||
public static double cameraBearingEqual = 1;
|
public static double cameraBearingEqual = 1;
|
||||||
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 mult = 0.0;
|
public static double mult = 0.0;
|
||||||
|
private boolean lockOffset = false;
|
||||||
public static double staticOffsetRate = -0.15;
|
|
||||||
public static double deltaAngleThreshold = 0.02;
|
|
||||||
public static double angleMultiplier = 0.0;
|
|
||||||
|
|
||||||
public static double fastSeekThreshold = 5.0; // Switch to medium mode below this
|
|
||||||
public static double mediumSeekThreshold = 2.0; // Switch to fine mode below this
|
|
||||||
public static double fastCorrectionGain = 0.75; // Correction gain for large errors
|
|
||||||
public static double mediumCorrectionGain = 0.4; // Correction gain for medium errors
|
|
||||||
public static double fineCorrectionGain = 0.2; // Correction gain for small errors
|
|
||||||
public static double maxOffsetChangePerCycle = 0.3; // Max offset change per cycle (degrees)
|
|
||||||
public static double finalInterpolation = 0.1; // Final position interpolation factor
|
|
||||||
|
|
||||||
|
|
||||||
// TODO: tune these values for limelight
|
|
||||||
|
|
||||||
public static double clampTolerance = 0.03;
|
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
Limelight3A webcam;
|
Limelight3A webcam;
|
||||||
|
private int obeliskID = 0;
|
||||||
|
private double offset = 0.0;
|
||||||
|
|
||||||
|
private PIDFController controller = new PIDFController(kP, kI, kD, kF);
|
||||||
double tx = 0.0;
|
double tx = 0.0;
|
||||||
double ty = 0.0;
|
double ty = 0.0;
|
||||||
double limelightPosX = 0.0;
|
double limelightPosX = 0.0;
|
||||||
double limelightPosY = 0.0;
|
double limelightPosY = 0.0;
|
||||||
private boolean lockOffset = false;
|
public static double clampTolerance = 0.03;
|
||||||
private int obeliskID = 0;
|
|
||||||
|
|
||||||
private double offset = 0.0;
|
|
||||||
|
|
||||||
public Turret(Robot rob, MultipleTelemetry tele, Limelight3A cam) {
|
public Turret(Robot rob, MultipleTelemetry tele, Limelight3A cam) {
|
||||||
this.TELE = tele;
|
this.TELE = tele;
|
||||||
this.robot = rob;
|
this.robot = rob;
|
||||||
this.webcam = cam;
|
this.webcam = cam;
|
||||||
webcam.start();
|
webcam.start();
|
||||||
if (redAlliance) {
|
if (redAlliance){
|
||||||
webcam.pipelineSwitch(3);
|
webcam.pipelineSwitch(3);
|
||||||
} else {
|
} else {
|
||||||
webcam.pipelineSwitch(2);
|
webcam.pipelineSwitch(2);
|
||||||
@@ -78,17 +78,17 @@ public class Turret {
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
public void manualSetTurret(double pos) {
|
public void manualSetTurret(double pos){
|
||||||
robot.turr1.setPosition(pos);
|
robot.turr1.setPosition(pos);
|
||||||
robot.turr2.setPosition(1 - pos);
|
robot.turr2.setPosition(1-pos);
|
||||||
}
|
}
|
||||||
|
|
||||||
public boolean turretEqual(double pos) {
|
public boolean turretEqual(double pos) {
|
||||||
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
|
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
|
||||||
}
|
}
|
||||||
|
|
||||||
private void limelightRead() { // only for tracking purposes, not general reads
|
private void limelightRead(){ // only for tracking purposes, not general reads
|
||||||
if (redAlliance) {
|
if (redAlliance){
|
||||||
webcam.pipelineSwitch(3);
|
webcam.pipelineSwitch(3);
|
||||||
} else {
|
} else {
|
||||||
webcam.pipelineSwitch(2);
|
webcam.pipelineSwitch(2);
|
||||||
@@ -101,7 +101,7 @@ public class Turret {
|
|||||||
ty = result.getTy();
|
ty = result.getTy();
|
||||||
// MegaTag1 code for receiving position
|
// MegaTag1 code for receiving position
|
||||||
Pose3D botpose = result.getBotpose();
|
Pose3D botpose = result.getBotpose();
|
||||||
if (botpose != null) {
|
if (botpose != null){
|
||||||
limelightPosX = botpose.getPosition().x;
|
limelightPosX = botpose.getPosition().x;
|
||||||
limelightPosY = botpose.getPosition().y;
|
limelightPosY = botpose.getPosition().y;
|
||||||
}
|
}
|
||||||
@@ -116,17 +116,17 @@ public class Turret {
|
|||||||
return tx;
|
return tx;
|
||||||
}
|
}
|
||||||
|
|
||||||
public double getTy() {
|
public double getTy(){
|
||||||
limelightRead();
|
limelightRead();
|
||||||
return ty;
|
return ty;
|
||||||
}
|
}
|
||||||
|
|
||||||
public double getLimelightX() {
|
public double getLimelightX(){
|
||||||
limelightRead();
|
limelightRead();
|
||||||
return limelightPosX;
|
return limelightPosX;
|
||||||
}
|
}
|
||||||
|
|
||||||
public double getLimelightY() {
|
public double getLimelightY(){
|
||||||
limelightRead();
|
limelightRead();
|
||||||
return limelightPosY;
|
return limelightPosY;
|
||||||
}
|
}
|
||||||
@@ -158,9 +158,9 @@ public class Turret {
|
|||||||
/*
|
/*
|
||||||
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
|
||||||
*/
|
*/
|
||||||
|
|
||||||
public void trackGoal(Pose2d deltaPos) {
|
public void trackGoal(Pose2d deltaPos) {
|
||||||
|
|
||||||
|
controller.setPIDF(kP, kI, kD, kF);
|
||||||
/* ---------------- FIELD → TURRET GEOMETRY ---------------- */
|
/* ---------------- FIELD → TURRET GEOMETRY ---------------- */
|
||||||
|
|
||||||
// Angle from robot to goal in robot frame
|
// Angle from robot to goal in robot frame
|
||||||
@@ -173,75 +173,55 @@ 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;
|
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 ---------------- */
|
||||||
/* ---------------- LIMELIGHT VISION CORRECTION ---------------- */
|
//
|
||||||
|
|
||||||
double tagBearingDeg = getBearing(); // + = target is to the left
|
double tagBearingDeg = getBearing(); // + = target is to the left
|
||||||
boolean hasValidTarget = (tagBearingDeg != 1000.0);
|
|
||||||
|
|
||||||
// Apply persistent offset from previous corrections
|
|
||||||
turretAngleDeg += offset;
|
turretAngleDeg += offset;
|
||||||
|
|
||||||
// Active correction if we see the target
|
/* ---------------- ANGLE → SERVO ---------------- */
|
||||||
if (hasValidTarget && !lockOffset) {
|
|
||||||
double bearingError = Math.abs(tagBearingDeg);
|
|
||||||
|
|
||||||
if (bearingError > cameraBearingEqual) {
|
double turretPos = turrDefault + (turretAngleDeg * (turret180Range * 2.0) / 360);
|
||||||
// Dual-mode correction: fast when far, gentle when close
|
|
||||||
double correctionGain;
|
// Clamp to servo range
|
||||||
if (bearingError > fastSeekThreshold) {
|
double currentEncoderPos = this.getTurrPos();
|
||||||
correctionGain = fastCorrectionGain;
|
|
||||||
} else if (bearingError > mediumSeekThreshold) {
|
if (!turretEqual(turretPos)) {
|
||||||
correctionGain = mediumCorrectionGain;
|
double diff = turretPos - currentEncoderPos;
|
||||||
} else {
|
turretPos = turretPos + diff * mult;
|
||||||
correctionGain = fineCorrectionGain;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Immediate correction to turret angle
|
if (currentEncoderPos < (turrMin + clampTolerance) || currentEncoderPos > (turrMax - clampTolerance)) {
|
||||||
turretAngleDeg -= tagBearingDeg * correctionGain;
|
// Clamp to servo range
|
||||||
|
turretPos = Math.max(turrMin, Math.min(turretPos, turrMax));
|
||||||
|
} else { // TODO: add so it only adds error when standstill
|
||||||
|
if (tagBearingDeg != 1000.0 && Math.abs(tagBearingDeg) > cameraBearingEqual && !lockOffset) {
|
||||||
|
// PID-based offset correction for faster, smoother tracking
|
||||||
|
|
||||||
|
// Proportional: respond to current error
|
||||||
|
|
||||||
|
offset = -controller.calculate(tagBearingDeg);
|
||||||
|
|
||||||
|
|
||||||
// Learn offset slowly for persistent calibration
|
|
||||||
double offsetChange = -tagBearingDeg * errorLearningRate;
|
|
||||||
// Rate limit to prevent oscillation
|
|
||||||
offsetChange = Math.max(-maxOffsetChangePerCycle, Math.min(offsetChange, maxOffsetChangePerCycle));
|
|
||||||
offset += offsetChange;
|
|
||||||
|
|
||||||
TELE.addData("Correction Mode", bearingError > fastSeekThreshold ? "FAST" :
|
|
||||||
bearingError > mediumSeekThreshold ? "MEDIUM" : "FINE");
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
/* ---------------- ANGLE → SERVO POSITION ---------------- */
|
|
||||||
|
|
||||||
double targetTurretPos = turrDefault + (turretAngleDeg * (turret180Range * 2.0) / 360);
|
|
||||||
|
|
||||||
// Clamp to physical servo limits
|
|
||||||
targetTurretPos = Math.max(turrMin, Math.min(targetTurretPos, turrMax));
|
|
||||||
|
|
||||||
// Interpolate towards target position
|
|
||||||
double currentPos = getTurrPos();
|
|
||||||
double turretPos = currentPos + (targetTurretPos - currentPos) * finalInterpolation;
|
|
||||||
|
|
||||||
// Set servo positions
|
|
||||||
robot.turr1.setPosition(turretPos);
|
robot.turr1.setPosition(turretPos);
|
||||||
robot.turr2.setPosition(1.0 - turretPos);
|
robot.turr2.setPosition(1.0 - turretPos);
|
||||||
|
|
||||||
|
|
||||||
/* ---------------- TELEMETRY ---------------- */
|
/* ---------------- TELEMETRY ---------------- */
|
||||||
|
|
||||||
TELE.addData("Turret Angle (deg)", "%.2f", turretAngleDeg);
|
TELE.addData("Turret Angle", turretAngleDeg);
|
||||||
TELE.addData("Target Pos", "%.3f", targetTurretPos);
|
TELE.addData("Bearing", tagBearingDeg);
|
||||||
TELE.addData("Current Pos", "%.3f", currentPos);
|
TELE.addData("Offset", offset);
|
||||||
TELE.addData("Commanded Pos", "%.3f", turretPos);
|
|
||||||
TELE.addData("Bearing Error", hasValidTarget ? String.format("%.2f", tagBearingDeg) : "NO TARGET");
|
|
||||||
TELE.addData("Learned Offset", "%.2f", offset);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -25,5 +25,9 @@ allprojects {
|
|||||||
}
|
}
|
||||||
|
|
||||||
repositories {
|
repositories {
|
||||||
|
repositories {
|
||||||
mavenCentral()
|
mavenCentral()
|
||||||
|
google()
|
||||||
|
maven { url 'https://maven.pedropathing.com' }
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user