Compare commits
8 Commits
7ffc51f60a
...
SpindexerU
| Author | SHA1 | Date | |
|---|---|---|---|
| d1434fbaa8 | |||
| d216ce78fc | |||
| 8dc03adfd3 | |||
| fefeeb1f2e | |||
| b5a31afe52 | |||
| 8d29a80696 | |||
| 5922f4e935 | |||
| 78d38481a7 |
@@ -5,11 +5,11 @@ import com.acmerobotics.dashboard.config.Config;
|
|||||||
@Config
|
@Config
|
||||||
public class ServoPositions {
|
public class ServoPositions {
|
||||||
|
|
||||||
public static double spindexer_intakePos1 = 0.19;
|
public static double spindexer_intakePos1 = 0.18;
|
||||||
|
|
||||||
public static double spindexer_intakePos2 = 0.35;//0.5;
|
public static double spindexer_intakePos2 = 0.36;//0.5;
|
||||||
|
|
||||||
public static double spindexer_intakePos3 = 0.51;//0.66;
|
public static double spindexer_intakePos3 = 0.54;//0.66;
|
||||||
|
|
||||||
public static double spindexer_outtakeBall3 = 0.47;
|
public static double spindexer_outtakeBall3 = 0.47;
|
||||||
|
|
||||||
|
|||||||
@@ -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));
|
||||||
@@ -818,6 +814,8 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
TELE.addData("hood", robot.hood.getPosition());
|
TELE.addData("hood", robot.hood.getPosition());
|
||||||
TELE.addData("targetVel", vel);
|
TELE.addData("targetVel", vel);
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
TELE.addData("Velocity", flywheel.getVelo());
|
||||||
|
TELE.addData("Velo1", flywheel.velo1);
|
||||||
|
TELE.addData("Velo2", flywheel.velo2);
|
||||||
TELE.addData("shootOrder", shootOrder);
|
TELE.addData("shootOrder", shootOrder);
|
||||||
TELE.addData("oddColor", oddBallColor);
|
TELE.addData("oddColor", oddBallColor);
|
||||||
|
|
||||||
|
|||||||
@@ -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);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,5 +1,6 @@
|
|||||||
package org.firstinspires.ftc.teamcode.tests;
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
|
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;
|
||||||
|
|
||||||
@@ -12,28 +13,40 @@ import com.qualcomm.robotcore.hardware.DcMotorEx;
|
|||||||
|
|
||||||
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.Spindexer;
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
@TeleOp
|
@TeleOp
|
||||||
public class ShooterTest extends LinearOpMode {
|
public class ShooterTest extends LinearOpMode {
|
||||||
|
public static int mode = 1;
|
||||||
public static int mode = 0;
|
|
||||||
public static double parameter = 0.0;
|
public static double parameter = 0.0;
|
||||||
// --- CONSTANTS YOU TUNE ---
|
// --- CONSTANTS YOU TUNE ---
|
||||||
|
|
||||||
//TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED
|
//TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED
|
||||||
public static double Velocity = 0.0;
|
public static double Velocity = 0.0;
|
||||||
public static double P = 40.0;
|
public static double P = 255.0;
|
||||||
public static double I = 0.3;
|
public static double I = 0.0;
|
||||||
public static double D = 7.0;
|
public static double D = 0.0;
|
||||||
public static double F = 10.0;
|
public static double F = 7.5;
|
||||||
public static double transferPower = 1.0;
|
public static double transferPower = 1.0;
|
||||||
public static double hoodPos = 0.501;
|
public static double hoodPos = 0.501;
|
||||||
public static double turretPos = 0.501;
|
public static double turretPos = 0.501;
|
||||||
public static boolean shoot = false;
|
public static boolean shoot = false;
|
||||||
|
|
||||||
|
public static boolean intake = false;
|
||||||
Robot robot;
|
Robot robot;
|
||||||
Flywheel flywheel;
|
Flywheel flywheel;
|
||||||
|
|
||||||
|
double shootStamp = 0.0;
|
||||||
|
boolean shootAll = false;
|
||||||
|
|
||||||
|
public double spinPow = 0.09;
|
||||||
|
|
||||||
|
public static boolean enableHoodAutoOpen = false;
|
||||||
|
public double hoodAdjust = 0.0;
|
||||||
|
public static double hoodAdjustFactor = 1.0;
|
||||||
|
Spindexer spindexer ;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
@@ -41,6 +54,7 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
DcMotorEx leftShooter = robot.shooter1;
|
DcMotorEx leftShooter = robot.shooter1;
|
||||||
DcMotorEx rightShooter = robot.shooter2;
|
DcMotorEx rightShooter = robot.shooter2;
|
||||||
flywheel = new Flywheel(hardwareMap);
|
flywheel = new Flywheel(hardwareMap);
|
||||||
|
spindexer = new Spindexer(hardwareMap);
|
||||||
|
|
||||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
MultipleTelemetry TELE = new MultipleTelemetry(
|
||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
@@ -61,15 +75,60 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
|
|
||||||
if (hoodPos != 0.501) {
|
if (hoodPos != 0.501) {
|
||||||
|
if (enableHoodAutoOpen) {
|
||||||
|
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)));
|
||||||
|
} else {
|
||||||
robot.hood.setPosition(hoodPos);
|
robot.hood.setPosition(hoodPos);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (intake) {
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
robot.transfer.setPower(transferPower);
|
|
||||||
if (shoot) {
|
if (shoot) {
|
||||||
|
shootStamp = getRuntime();
|
||||||
|
shootAll = true;
|
||||||
|
shoot = false;
|
||||||
|
robot.transfer.setPower(transferPower);
|
||||||
|
}
|
||||||
|
if (shootAll) {
|
||||||
|
|
||||||
|
//intake = false;
|
||||||
|
//reject = false;
|
||||||
|
|
||||||
|
// TODO: Change starting position based on desired order to shoot green ball
|
||||||
|
//spindexPos = spindexer_intakePos1;
|
||||||
|
|
||||||
|
if (getRuntime() - shootStamp < 3.5) {
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_in);
|
robot.transferServo.setPosition(transferServo_in);
|
||||||
|
|
||||||
|
robot.spin1.setPower(-spinPow);
|
||||||
|
robot.spin2.setPower(spinPow);
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
//spindexPos = spindexer_intakePos1;
|
||||||
|
|
||||||
|
shootAll = false;
|
||||||
|
|
||||||
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
robot.transfer.setPower(0);
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
|
||||||
|
spindexer.resetSpindexer();
|
||||||
|
spindexer.processIntake();
|
||||||
}
|
}
|
||||||
|
} else {
|
||||||
|
spindexer.processIntake();
|
||||||
|
}
|
||||||
|
|
||||||
TELE.addData("Velocity", flywheel.getVelo());
|
TELE.addData("Velocity", flywheel.getVelo());
|
||||||
TELE.addData("Velocity 1", flywheel.getVelo1());
|
TELE.addData("Velocity 1", flywheel.getVelo1());
|
||||||
TELE.addData("Velocity 2", flywheel.getVelo2());
|
TELE.addData("Velocity 2", flywheel.getVelo2());
|
||||||
|
|||||||
@@ -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();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -9,8 +9,8 @@ public class Flywheel {
|
|||||||
Robot robot;
|
Robot robot;
|
||||||
public PIDFCoefficients shooterPIDF1, shooterPIDF2;
|
public PIDFCoefficients shooterPIDF1, shooterPIDF2;
|
||||||
double velo = 0.0;
|
double velo = 0.0;
|
||||||
double velo1 = 0.0;
|
public double velo1 = 0.0;
|
||||||
double velo2 = 0.0;
|
public double velo2 = 0.0;
|
||||||
double targetVelocity = 0.0;
|
double targetVelocity = 0.0;
|
||||||
double powPID = 0.0;
|
double powPID = 0.0;
|
||||||
boolean steady = false;
|
boolean steady = false;
|
||||||
@@ -38,10 +38,14 @@ public class Flywheel {
|
|||||||
|
|
||||||
// Set the robot PIDF for the next cycle.
|
// Set the robot PIDF for the next cycle.
|
||||||
public void setPIDF(double p, double i, double d, double f) {
|
public void setPIDF(double p, double i, double d, double f) {
|
||||||
robot.shooterPIDF.p = p;
|
shooterPIDF1.p = p;
|
||||||
robot.shooterPIDF.i = i;
|
shooterPIDF1.i = i;
|
||||||
robot.shooterPIDF.d = d;
|
shooterPIDF1.d = d;
|
||||||
robot.shooterPIDF.f = f;
|
shooterPIDF1.f = f;
|
||||||
|
shooterPIDF2.p = p;
|
||||||
|
shooterPIDF2.i = i;
|
||||||
|
shooterPIDF2.d = d;
|
||||||
|
shooterPIDF2.f = f;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Convert from RPM to Ticks per Second
|
// Convert from RPM to Ticks per Second
|
||||||
@@ -54,10 +58,6 @@ public class Flywheel {
|
|||||||
targetVelocity = commandedVelocity;
|
targetVelocity = commandedVelocity;
|
||||||
|
|
||||||
// Add code here to set PIDF based on desired RPM
|
// 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, shooterPIDF1);
|
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
|
||||||
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
||||||
|
|||||||
@@ -29,10 +29,10 @@ public class Robot {
|
|||||||
public DcMotorEx intake;
|
public DcMotorEx intake;
|
||||||
public DcMotorEx transfer;
|
public DcMotorEx transfer;
|
||||||
public PIDFCoefficients shooterPIDF;
|
public PIDFCoefficients shooterPIDF;
|
||||||
public double shooterPIDF_P = 10.0;
|
public double shooterPIDF_P = 255.0;
|
||||||
public double shooterPIDF_I = 0.6;
|
public double shooterPIDF_I = 0.0;
|
||||||
public double shooterPIDF_D = 5.0;
|
public double shooterPIDF_D = 0.0;
|
||||||
public double shooterPIDF_F = 10.0;
|
public double shooterPIDF_F = 7.5;
|
||||||
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 shooter1;
|
||||||
public DcMotorEx shooter2;
|
public DcMotorEx shooter2;
|
||||||
|
|||||||
@@ -8,7 +8,7 @@ import com.qualcomm.robotcore.hardware.HardwareMap;
|
|||||||
public class Servos {
|
public class Servos {
|
||||||
//PID constants
|
//PID constants
|
||||||
// TODO: get PIDF constants
|
// TODO: get PIDF constants
|
||||||
public static double spinP = 3.3, spinI = 0, spinD = 0.1, spinF = 0.02;
|
public static double spinP = 2.0, spinI = 0, spinD = 0.3, spinF = 0.02;
|
||||||
public static double turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0;
|
public static double turrP = 1.1, turrI = 0.25, turrD = 0.0625, turrF = 0;
|
||||||
public static double spin_scalar = 1.0086;
|
public static double spin_scalar = 1.0086;
|
||||||
public static double spin_restPos = 0.0;
|
public static double spin_restPos = 0.0;
|
||||||
@@ -40,7 +40,7 @@ public class Servos {
|
|||||||
}
|
}
|
||||||
|
|
||||||
public boolean spinEqual(double pos) {
|
public boolean spinEqual(double pos) {
|
||||||
return Math.abs(pos - this.getSpinPos()) < 0.02;
|
return Math.abs(pos - this.getSpinPos()) < 0.03;
|
||||||
}
|
}
|
||||||
|
|
||||||
public double getTurrPos() {
|
public double getTurrPos() {
|
||||||
|
|||||||
@@ -277,7 +277,6 @@ public class Spindexer {
|
|||||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||||
currentIntakeState = Spindexer.IntakeState.UNKNOWN_DETECT;
|
currentIntakeState = Spindexer.IntakeState.UNKNOWN_DETECT;
|
||||||
stopSpindexer();
|
stopSpindexer();
|
||||||
detectBalls(true, true);
|
|
||||||
unknownColorDetect = 0;
|
unknownColorDetect = 0;
|
||||||
} else {
|
} else {
|
||||||
// Keep moving the spindexer
|
// Keep moving the spindexer
|
||||||
@@ -288,7 +287,7 @@ public class Spindexer {
|
|||||||
if (unknownColorDetect >5) {
|
if (unknownColorDetect >5) {
|
||||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||||
} else {
|
} else {
|
||||||
detectBalls(true, true);
|
//detectBalls(true, true);
|
||||||
unknownColorDetect++;
|
unknownColorDetect++;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
@@ -343,7 +342,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(false, false);
|
//detectBalls(false, false);
|
||||||
} else {
|
} else {
|
||||||
// Keep moving the spindexer
|
// Keep moving the spindexer
|
||||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
@@ -374,7 +373,7 @@ public class Spindexer {
|
|||||||
|
|
||||||
case SHOOT_ALL_READY:
|
case SHOOT_ALL_READY:
|
||||||
// Double Check Colors
|
// Double Check Colors
|
||||||
detectBalls(false, false); // Minimize hardware calls
|
//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) {
|
||||||
// All ball shot move to intake state
|
// All ball shot move to intake state
|
||||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||||
@@ -422,7 +421,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(true, false);
|
//detectBalls(true, false);
|
||||||
} else {
|
} else {
|
||||||
// Keep moving the spindexer
|
// Keep moving the spindexer
|
||||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
|
|||||||
@@ -9,8 +9,8 @@ import com.qualcomm.robotcore.hardware.HardwareMap;
|
|||||||
public class Targeting {
|
public class Targeting {
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
double cancelOffsetX = 7.071067811;
|
double cancelOffsetX = 0.0; // was -40.0
|
||||||
double cancelOffsetY = 7.071067811;
|
double cancelOffsetY = 0.0; // was 7.0
|
||||||
double unitConversionFactor = 0.95;
|
double unitConversionFactor = 0.95;
|
||||||
|
|
||||||
int tileSize = 24; //inches
|
int tileSize = 24; //inches
|
||||||
@@ -37,33 +37,33 @@ public class Targeting {
|
|||||||
static {
|
static {
|
||||||
KNOWNTARGETING = new Settings[6][6];
|
KNOWNTARGETING = new Settings[6][6];
|
||||||
// ROW 0 - Closet to the goals
|
// ROW 0 - Closet to the goals
|
||||||
KNOWNTARGETING[0][0] = new Settings (3000.0, 0.25);
|
KNOWNTARGETING[0][0] = new Settings (2300.0, 0.93);
|
||||||
KNOWNTARGETING[0][1] = new Settings (3001.0, 0.25);
|
KNOWNTARGETING[0][1] = new Settings (2300.0, 0.93);
|
||||||
KNOWNTARGETING[0][2] = new Settings (3002.0, 0.25);
|
KNOWNTARGETING[0][2] = new Settings (2500.0, 0.78);
|
||||||
KNOWNTARGETING[0][3] = new Settings (3302.0, 0.2);
|
KNOWNTARGETING[0][3] = new Settings (2800.0, 0.68);
|
||||||
KNOWNTARGETING[0][4] = new Settings (3503.0, 0.15);
|
KNOWNTARGETING[0][4] = new Settings (3000.0, 0.58);
|
||||||
KNOWNTARGETING[0][5] = new Settings (3505.0, 0.15);
|
KNOWNTARGETING[0][5] = new Settings (3000.0, 0.58);
|
||||||
// ROW 1
|
// ROW 1
|
||||||
KNOWNTARGETING[1][0] = new Settings (3010.0, 0.25);
|
KNOWNTARGETING[1][0] = new Settings (2300.0, 0.93);
|
||||||
KNOWNTARGETING[1][1] = new Settings (3011.0, 0.25);
|
KNOWNTARGETING[1][1] = new Settings (2300.0, 0.93);
|
||||||
KNOWNTARGETING[1][2] = new Settings (3012.0, 0.25);
|
KNOWNTARGETING[1][2] = new Settings (2600.0, 0.78);
|
||||||
KNOWNTARGETING[1][3] = new Settings (3313.0, 0.15);
|
KNOWNTARGETING[1][3] = new Settings (2800.0, 0.62);
|
||||||
KNOWNTARGETING[1][4] = new Settings (3514.0, 0.15);
|
KNOWNTARGETING[1][4] = new Settings (3000.0, 0.55);
|
||||||
KNOWNTARGETING[1][5] = new Settings (3515.0, 0.15);
|
KNOWNTARGETING[1][5] = new Settings (3200.0, 0.50);
|
||||||
// ROW 2
|
// ROW 2
|
||||||
KNOWNTARGETING[2][0] = new Settings (3020.0, 0.1);
|
KNOWNTARGETING[2][0] = new Settings (2500.0, 0.78);
|
||||||
KNOWNTARGETING[2][1] = new Settings (3000.0, 0.25);
|
KNOWNTARGETING[2][1] = new Settings (2500.0, 0.78);
|
||||||
KNOWNTARGETING[2][2] = new Settings (3000.0, 0.15);
|
KNOWNTARGETING[2][2] = new Settings (2700.0, 0.60);
|
||||||
KNOWNTARGETING[2][3] = new Settings (3000.0, 0.15);
|
KNOWNTARGETING[2][3] = new Settings (2900.0, 0.53);
|
||||||
KNOWNTARGETING[2][4] = new Settings (3524.0, 0.15);
|
KNOWNTARGETING[2][4] = new Settings (3100.0, 0.50);
|
||||||
KNOWNTARGETING[2][5] = new Settings (3525.0, 0.15);
|
KNOWNTARGETING[2][5] = new Settings (3100.0, 0.50);
|
||||||
// ROW 3
|
// ROW 3
|
||||||
KNOWNTARGETING[3][0] = new Settings (3030.0, 0.15);
|
KNOWNTARGETING[3][0] = new Settings (2900.0, 0.50);
|
||||||
KNOWNTARGETING[3][1] = new Settings (3031.0, 0.15);
|
KNOWNTARGETING[3][1] = new Settings (2900.0, 0.50);
|
||||||
KNOWNTARGETING[3][2] = new Settings (3000.0, 0.15);
|
KNOWNTARGETING[3][2] = new Settings (2900.0, 0.50);
|
||||||
KNOWNTARGETING[3][3] = new Settings (3000.0, 0.15);
|
KNOWNTARGETING[3][3] = new Settings (3100.0, 0.47);
|
||||||
KNOWNTARGETING[3][4] = new Settings (3000.0, 0.03);
|
KNOWNTARGETING[3][4] = new Settings (3100.0, 0.47);
|
||||||
KNOWNTARGETING[3][5] = new Settings (3535.0, 0.1);
|
KNOWNTARGETING[3][5] = new Settings (3100.0, 0.47);
|
||||||
// ROW 4
|
// ROW 4
|
||||||
KNOWNTARGETING[4][0] = new Settings (4540.0, 0.1);
|
KNOWNTARGETING[4][0] = new Settings (4540.0, 0.1);
|
||||||
KNOWNTARGETING[4][1] = new Settings (4541.0, 0.1);
|
KNOWNTARGETING[4][1] = new Settings (4541.0, 0.1);
|
||||||
@@ -89,8 +89,8 @@ public class Targeting {
|
|||||||
|
|
||||||
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 + cancelOffsetX) * sin45 + (robotY + cancelOffsetY) * cos45;
|
||||||
double rotatedX = (robotX - 40.0) * cos45 - (robotY + 7.0) * sin45;
|
double rotatedX = (robotX + cancelOffsetX) * cos45 - (robotY + cancelOffsetY) * sin45;
|
||||||
|
|
||||||
// Convert robot coordinates to inches
|
// Convert robot coordinates to inches
|
||||||
robotInchesX = rotatedX * unitConversionFactor;
|
robotInchesX = rotatedX * unitConversionFactor;
|
||||||
@@ -107,8 +107,8 @@ public class Targeting {
|
|||||||
// basic search
|
// basic search
|
||||||
if(!interpolate) {
|
if(!interpolate) {
|
||||||
if ((robotGridY < 6) && (robotGridX <6)) {
|
if ((robotGridY < 6) && (robotGridX <6)) {
|
||||||
recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridY][robotGridX].flywheelRPM;
|
recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridX][robotGridY].flywheelRPM;
|
||||||
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridY][robotGridX].hoodAngle;
|
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridX][robotGridY].hoodAngle;
|
||||||
}
|
}
|
||||||
return recommendedSettings;
|
return recommendedSettings;
|
||||||
} else {
|
} else {
|
||||||
|
|||||||
@@ -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,45 +18,43 @@ 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;
|
||||||
@@ -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);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -24,6 +24,10 @@ allprojects {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
repositories {
|
||||||
repositories {
|
repositories {
|
||||||
mavenCentral()
|
mavenCentral()
|
||||||
|
google()
|
||||||
|
maven { url 'https://maven.pedropathing.com' }
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user