Compare commits
3 Commits
SpindexerU
...
LimelightP
| Author | SHA1 | Date | |
|---|---|---|---|
| 04372ec410 | |||
| e665ddf032 | |||
| b08fe5ada5 |
@@ -305,33 +305,32 @@ public class Spindexer {
|
|||||||
// Find Next Open Position and start movement
|
// Find Next Open Position and start movement
|
||||||
double currentSpindexerPos = servos.getSpinPos();
|
double currentSpindexerPos = servos.getSpinPos();
|
||||||
double commandedtravelDistance = 2.0;
|
double commandedtravelDistance = 2.0;
|
||||||
double proposedTravelDistance = Math.abs(intakePositions[0] - currentSpindexerPos);
|
//double proposedTravelDistance = Math.abs(intakePositions[0] - currentSpindexerPos);
|
||||||
if (ballPositions[0].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
//if (ballPositions[0].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||||
|
if (ballPositions[0].isEmpty) {
|
||||||
// Position 1
|
// Position 1
|
||||||
commandedIntakePosition = 0;
|
commandedIntakePosition = 0;
|
||||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||||
commandedtravelDistance = proposedTravelDistance;
|
|
||||||
}
|
}
|
||||||
proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos);
|
//proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos);
|
||||||
if (ballPositions[1].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
//if (ballPositions[1].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||||
|
if (ballPositions[1].isEmpty) {
|
||||||
// Position 2
|
// Position 2
|
||||||
commandedIntakePosition = 1;
|
commandedIntakePosition = 1;
|
||||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||||
commandedtravelDistance = proposedTravelDistance;
|
|
||||||
}
|
}
|
||||||
proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos);
|
//proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos);
|
||||||
if (ballPositions[2].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
if (ballPositions[2].isEmpty) {
|
||||||
// Position 3
|
// Position 3
|
||||||
commandedIntakePosition = 2;
|
commandedIntakePosition = 2;
|
||||||
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||||
currentIntakeState = Spindexer.IntakeState.MOVING;
|
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||||
commandedtravelDistance = proposedTravelDistance;
|
|
||||||
}
|
}
|
||||||
if (currentIntakeState != Spindexer.IntakeState.MOVING) {
|
if (currentIntakeState != Spindexer.IntakeState.MOVING) {
|
||||||
// Full
|
// Full
|
||||||
commandedIntakePosition = bestFitMotif();
|
//commandedIntakePosition = bestFitMotif();
|
||||||
currentIntakeState = Spindexer.IntakeState.FULL;
|
currentIntakeState = Spindexer.IntakeState.FULL;
|
||||||
}
|
}
|
||||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
|
|||||||
@@ -14,6 +14,8 @@ public class Targeting {
|
|||||||
double unitConversionFactor = 0.95;
|
double unitConversionFactor = 0.95;
|
||||||
|
|
||||||
int tileSize = 24; //inches
|
int tileSize = 24; //inches
|
||||||
|
public final int TILE_UPPER_QUARTILE = 18;
|
||||||
|
public final int TILE_LOWER_QUARTILE = 6;
|
||||||
|
|
||||||
public double robotInchesX, robotInchesY = 0.0;
|
public double robotInchesX, robotInchesY = 0.0;
|
||||||
|
|
||||||
@@ -100,6 +102,60 @@ public class Targeting {
|
|||||||
int gridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) + 1);
|
int gridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) + 1);
|
||||||
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
|
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
|
||||||
|
|
||||||
|
int remX = Math.floorMod((int)robotInchesX, tileSize);
|
||||||
|
int remY = Math.floorMod((int)robotInchesX, tileSize);
|
||||||
|
|
||||||
|
// Determine if we need to interpolate based on tile position.
|
||||||
|
// if near upper or lower quarter or tile interpolate with next tile.
|
||||||
|
int x1 = 0;
|
||||||
|
int y1 = 0;
|
||||||
|
// interpolate = false;
|
||||||
|
// if ((remX > TILE_UPPER_QUARTILE) && (remY > TILE_UPPER_QUARTILE) &&
|
||||||
|
// (robotGridX < 5) && (robotGridY <5)) {
|
||||||
|
// // +X, +Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX + 1;
|
||||||
|
// y1 = robotGridY + 1;
|
||||||
|
// } else if ((remX < TILE_LOWER_QUARTILE) && (remY < TILE_LOWER_QUARTILE) &&
|
||||||
|
// (robotGridX > 0) && (robotGridY > 0)) {
|
||||||
|
// // -X, -Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX - 1;
|
||||||
|
// y1 = robotGridY - 1;
|
||||||
|
// } else if ((remX > TILE_UPPER_QUARTILE) && (remY < TILE_LOWER_QUARTILE) &&
|
||||||
|
// (robotGridX < 5) && (robotGridY > 0)) {
|
||||||
|
// // +X, -Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX + 1;
|
||||||
|
// y1 = robotGridY - 1;
|
||||||
|
// } else if ((remX < TILE_LOWER_QUARTILE) && (remY > TILE_UPPER_QUARTILE) &&
|
||||||
|
// (robotGridX > 0) && (robotGridY < 5)) {
|
||||||
|
// // -X, +Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX - 1;
|
||||||
|
// y1 = robotGridY + 1;
|
||||||
|
// } else if ((remX < TILE_LOWER_QUARTILE) && (robotGridX > 0)) {
|
||||||
|
// // -X, Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX - 1;
|
||||||
|
// y1 = robotGridY;
|
||||||
|
// } else if ((remY < TILE_LOWER_QUARTILE) && (robotGridY > 0)) {
|
||||||
|
// // X, -Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX;
|
||||||
|
// y1 = robotGridY - 1;
|
||||||
|
// } else if ((remX > TILE_UPPER_QUARTILE) && (robotGridX < 5)) {
|
||||||
|
// // +X, Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX + 1;
|
||||||
|
// y1 = robotGridY;
|
||||||
|
// } else if ((remY > TILE_UPPER_QUARTILE) && (robotGridY < 5)) {
|
||||||
|
// // X, +Y
|
||||||
|
// interpolate = true;
|
||||||
|
// x1 = robotGridX;
|
||||||
|
// y1 = robotGridY + 1;
|
||||||
|
// }
|
||||||
|
|
||||||
//clamp
|
//clamp
|
||||||
robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
||||||
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
||||||
@@ -115,9 +171,9 @@ public class Targeting {
|
|||||||
|
|
||||||
// bilinear interpolation
|
// bilinear interpolation
|
||||||
int x0 = robotGridX;
|
int x0 = robotGridX;
|
||||||
int x1 = Math.min(x0 + 1, KNOWNTARGETING[0].length - 1);
|
//int x1 = Math.min(x0 + 1, KNOWNTARGETING[0].length - 1);
|
||||||
int y0 = gridY;
|
int y0 = robotGridY;
|
||||||
int y1 = Math.min(y0 + 1, KNOWNTARGETING.length - 1);
|
//int y1 = Math.min(y0 + 1, KNOWNTARGETING.length - 1);
|
||||||
|
|
||||||
double x = (robotInchesX - (x0 * tileSize)) / tileSize;
|
double x = (robotInchesX - (x0 * tileSize)) / tileSize;
|
||||||
double y = (robotInchesY - (y0 * tileSize)) / tileSize;
|
double y = (robotInchesY - (y0 * tileSize)) / tileSize;
|
||||||
|
|||||||
@@ -1,12 +1,13 @@
|
|||||||
|
|
||||||
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;
|
||||||
|
|
||||||
|
import static java.lang.Math.abs;
|
||||||
|
|
||||||
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.arcrobotics.ftclib.controller.PIDController;
|
||||||
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;
|
||||||
@@ -18,54 +19,55 @@ 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;
|
||||||
|
public static double turrMin = 0.15;
|
||||||
|
public static double turrMax = 0.85;
|
||||||
|
|
||||||
|
public static double visionCorrectionGain = 0.08; // Single tunable gain
|
||||||
|
public static double maxOffsetChangePerCycle = 5.0; // Degrees per cycle
|
||||||
|
public static double cameraBearingEqual = 0.5; // Deadband
|
||||||
|
|
||||||
// TODO: tune these values for limelight
|
// 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 clampTolerance = 0.03;
|
||||||
|
|
||||||
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 turrMin = 0.2;
|
|
||||||
public static double turrMax = 0.8;
|
|
||||||
public static double mult = 0.0;
|
|
||||||
private boolean lockOffset = false;
|
|
||||||
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;
|
||||||
public static double clampTolerance = 0.03;
|
private boolean lockOffset = false;
|
||||||
|
private int obeliskID = 0;
|
||||||
|
|
||||||
|
private double offset = 0.0;
|
||||||
|
private double currentTrackOffset = 0.0;
|
||||||
|
private int currentTrackCount = 0;
|
||||||
|
|
||||||
|
private double permanentOffset = 0.0;
|
||||||
|
|
||||||
|
LLResult result;
|
||||||
|
|
||||||
|
private PIDController bearingPID;
|
||||||
|
public static double B_PID_P = 0.3, B_PID_I = 0.0, B_PID_D = 0.05;
|
||||||
|
boolean bearingAligned = false;
|
||||||
|
|
||||||
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);
|
||||||
}
|
}
|
||||||
|
bearingPID = new PIDController(B_PID_P, B_PID_I, B_PID_D);
|
||||||
}
|
}
|
||||||
|
|
||||||
public void zeroTurretEncoder() {
|
public void zeroTurretEncoder() {
|
||||||
@@ -78,30 +80,30 @@ 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(4);
|
||||||
} else {
|
} else {
|
||||||
webcam.pipelineSwitch(2);
|
webcam.pipelineSwitch(2);
|
||||||
}
|
}
|
||||||
|
|
||||||
LLResult result = webcam.getLatestResult();
|
result = webcam.getLatestResult();
|
||||||
if (result != null) {
|
if (result != null) {
|
||||||
if (result.isValid()) {
|
if (result.isValid()) {
|
||||||
tx = result.getTx();
|
tx = result.getTx();
|
||||||
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 +118,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 +160,50 @@ 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
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
||||||
|
private double bearingAlign (LLResult llResult) {
|
||||||
|
double bearingOffset = 0.0;
|
||||||
|
double targetTx = llResult.getTx(); // How far left or right the target is (degrees)
|
||||||
|
final double MIN_OFFSET_POWER = 0.15;
|
||||||
|
final double TARGET_POSITION_TOLERANCE = 1.0;
|
||||||
|
// LL has 54.5 degree total Horizontal FOV; very edges are not useful.
|
||||||
|
final double HORIZONTAL_FOV_RANGE = 26.0; // Total usable horizontal degrees from center +/-
|
||||||
|
final double DRIVE_POWER_REDUCTION = 2.0;
|
||||||
|
|
||||||
|
if (abs(targetTx) < TARGET_POSITION_TOLERANCE) {
|
||||||
|
bearingAligned = true;
|
||||||
|
} else {
|
||||||
|
bearingAligned = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Only with valid data and if too far off target
|
||||||
|
if (llResult.isValid() && !bearingAligned)
|
||||||
|
{
|
||||||
|
|
||||||
|
// Adjust Robot Speed based on how far the target is located
|
||||||
|
// Only drive at half speed max
|
||||||
|
// switched to PID but original formula left for reference in comments
|
||||||
|
//drivePower = targetTx/HORIZONTAL_FOV_RANGE / DRIVE_POWER_REDUCTION;
|
||||||
|
bearingOffset = -(bearingPID.calculate(targetTx, 0.0));
|
||||||
|
|
||||||
|
// // Make sure we have enough power to actually drive the wheels
|
||||||
|
// if (abs(bearingOffset) < MIN_OFFSET_POWER) {
|
||||||
|
// if (bearingOffset > 0.0) {
|
||||||
|
// bearingOffset = MIN_OFFSET_POWER;
|
||||||
|
// } else {
|
||||||
|
// bearingOffset = -MIN_OFFSET_POWER;
|
||||||
|
// }
|
||||||
|
//
|
||||||
|
// }
|
||||||
|
}
|
||||||
|
|
||||||
|
return bearingOffset;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
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,55 +216,96 @@ 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 ---------------- */
|
||||||
|
// Update local limelight results
|
||||||
|
//double tagBearingDeg = getBearing(); // + = target is to the left
|
||||||
|
//boolean hasValidTarget = (tagBearingDeg != 1000.0);
|
||||||
|
|
||||||
|
turretAngleDeg += permanentOffset;
|
||||||
|
|
||||||
|
limelightRead();
|
||||||
|
// Active correction if we see the target
|
||||||
|
if (result.isValid() && !lockOffset) {
|
||||||
|
currentTrackOffset += bearingAlign(result);
|
||||||
|
currentTrackCount++;
|
||||||
|
// double bearingError = Math.abs(tagBearingDeg);
|
||||||
//
|
//
|
||||||
double tagBearingDeg = getBearing(); // + = target is to the left
|
// if (bearingError > cameraBearingEqual) {
|
||||||
|
// // Apply sqrt scaling to reduce aggressive corrections at large errors
|
||||||
turretAngleDeg += offset;
|
// double filteredBearing = Math.signum(tagBearingDeg) * Math.sqrt(Math.abs(tagBearingDeg));
|
||||||
|
//
|
||||||
/* ---------------- ANGLE → SERVO ---------------- */
|
// // Calculate correction
|
||||||
|
// double offsetChange = visionCorrectionGain * filteredBearing;
|
||||||
double turretPos = turrDefault + (turretAngleDeg * (turret180Range * 2.0) / 360);
|
//
|
||||||
|
// // Limit rate of change to prevent jumps
|
||||||
// Clamp to servo range
|
// offsetChange = Math.max(-maxOffsetChangePerCycle,
|
||||||
double currentEncoderPos = this.getTurrPos();
|
// Math.min(maxOffsetChangePerCycle, offsetChange));
|
||||||
|
//
|
||||||
if (!turretEqual(turretPos)) {
|
// // Accumulate the correction
|
||||||
double diff = turretPos - currentEncoderPos;
|
// offset += offsetChange;
|
||||||
turretPos = turretPos + diff * mult;
|
//
|
||||||
|
// TELE.addData("Bearing Error", tagBearingDeg);
|
||||||
|
// TELE.addData("Offset Change", offsetChange);
|
||||||
|
// TELE.addData("Total Offset", offset);
|
||||||
|
// } else {
|
||||||
|
// // When centered, lock in the learned offset
|
||||||
|
// permanentOffset = offset;
|
||||||
|
// offset = 0.0;
|
||||||
|
// }
|
||||||
|
} else {
|
||||||
|
// only store perma update after 20+ successful tracks
|
||||||
|
// this did not work good in testing; only current works best so far.
|
||||||
|
// if (currentTrackCount > 20) {
|
||||||
|
// offset = currentTrackOffset;
|
||||||
|
// }
|
||||||
|
currentTrackOffset = 0.0;
|
||||||
|
currentTrackCount = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (currentEncoderPos < (turrMin + clampTolerance) || currentEncoderPos > (turrMax - clampTolerance)) {
|
// Apply accumulated offset
|
||||||
// Clamp to servo range
|
turretAngleDeg += offset + currentTrackOffset;
|
||||||
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);
|
|
||||||
|
|
||||||
|
|
||||||
|
/* ---------------- 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 = targetTurretPos;
|
||||||
|
|
||||||
|
if (targetTurretPos == turrMin) {
|
||||||
|
turretPos = turrMin;
|
||||||
|
} else if (targetTurretPos == turrMax) {
|
||||||
|
turretPos = turrMax;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// 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", turretAngleDeg);
|
TELE.addData("Turret Angle (deg)", "%.2f", turretAngleDeg);
|
||||||
TELE.addData("Bearing", tagBearingDeg);
|
TELE.addData("Target Pos", "%.3f", targetTurretPos);
|
||||||
TELE.addData("Offset", offset);
|
TELE.addData("Current Pos", "%.3f", currentPos);
|
||||||
|
TELE.addData("Commanded Pos", "%.3f", turretPos);
|
||||||
|
TELE.addData("LL Valid", result.isValid());
|
||||||
|
TELE.addData("LL getTx", result.getTx());
|
||||||
|
TELE.addData("LL Offset", offset);
|
||||||
|
//TELE.addData("Bearing Error", hasValidTarget ? String.format("%.2f", tagBearingDeg) : "NO TARGET");
|
||||||
|
TELE.addData("Learned Offset", "%.2f", offset);
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user