Compare commits
16 Commits
c2e9d8fa87
...
SpindexerU
| Author | SHA1 | Date | |
|---|---|---|---|
| d1434fbaa8 | |||
| d216ce78fc | |||
| 8dc03adfd3 | |||
| 7ffc51f60a | |||
| 7625f9a640 | |||
| fefeeb1f2e | |||
| b5a31afe52 | |||
| 8d29a80696 | |||
| 5922f4e935 | |||
| 78d38481a7 | |||
| 8a4bfecbf8 | |||
| 3591e20001 | |||
| 4050a354f7 | |||
| 16ffdd003f | |||
| f20e640c62 | |||
| fbdeb6e291 |
@@ -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);
|
||||
|
||||
}
|
||||
|
||||
@@ -5,11 +5,11 @@ import com.acmerobotics.dashboard.config.Config;
|
||||
@Config
|
||||
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;
|
||||
|
||||
|
||||
@@ -21,4 +21,6 @@ public class ShooterVars {
|
||||
// VELOCITY CONSTANTS
|
||||
public static int AUTO_CLOSE_VEL = 3175; //3300;
|
||||
public static int AUTO_FAR_VEL = 4000; //TODO: test this
|
||||
|
||||
public static Types.Motif currentMotif = Types.Motif.NONE;
|
||||
}
|
||||
@@ -0,0 +1,10 @@
|
||||
package org.firstinspires.ftc.teamcode.constants;
|
||||
|
||||
public class Types {
|
||||
public enum Motif {
|
||||
NONE,
|
||||
GPP, // Green, Purple, Purple
|
||||
PGP, // Purple, Green, Purple
|
||||
PPG // Purple, Purple, Green
|
||||
}
|
||||
}
|
||||
@@ -1,4 +0,0 @@
|
||||
package org.firstinspires.ftc.teamcode.constants;
|
||||
|
||||
public class blank {
|
||||
}
|
||||
@@ -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,7 @@ 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.limelightvision.Limelight3A;
|
||||
import com.qualcomm.hardware.lynx.LynxModule;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
@@ -34,6 +32,7 @@ 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;
|
||||
@@ -50,8 +49,6 @@ public class TeleopV3 extends LinearOpMode {
|
||||
public static double spindexPos = spindexer_intakePos1;
|
||||
public static double spinPow = 0.09;
|
||||
public static double bMult = 1, bDiv = 2200;
|
||||
public static double limelightKp = 0.001; // Proportional gain for limelight auto-aim
|
||||
public static double limelightDeadband = 0.5; // Ignore tx values smaller than this
|
||||
public static double tp = 0.8, ti = 0.001, td = 0.0315, tf = 0;
|
||||
public static boolean manualTurret = true;
|
||||
public double vel = 3000;
|
||||
@@ -123,7 +120,7 @@ public class TeleopV3 extends LinearOpMode {
|
||||
private double transferStamp = 0.0;
|
||||
private int tickerA = 1;
|
||||
private boolean transferIn = false;
|
||||
boolean turretInterpolate = true;
|
||||
boolean turretInterpolate = false;
|
||||
|
||||
public static double velPrediction(double distance) {
|
||||
if (distance < 30) {
|
||||
@@ -155,7 +152,7 @@ public class TeleopV3 extends LinearOpMode {
|
||||
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||
spindexer = new Spindexer(hardwareMap);
|
||||
targeting = new Targeting();
|
||||
targetingSettings = new Targeting.Settings(0.0,0.0);
|
||||
targetingSettings = new Targeting.Settings(0.0, 0.0);
|
||||
|
||||
PIDFController tController = new PIDFController(tp, ti, td, tf);
|
||||
|
||||
@@ -169,6 +166,9 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
// robot.limelight.start();
|
||||
|
||||
Turret turret = new Turret(robot, TELE, robot.limelight);
|
||||
waitForStart();
|
||||
|
||||
waitForStart();
|
||||
if (isStopRequested()) return;
|
||||
|
||||
@@ -382,40 +382,20 @@ 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;
|
||||
|
||||
desiredTurretAngle += manualOffset + error;
|
||||
|
||||
offset = desiredTurretAngle - 180 - (Math.toDegrees(robotHeading - headingOffset));
|
||||
|
||||
if (offset > 135) {
|
||||
offset -= 360;
|
||||
}
|
||||
|
||||
double pos = turrDefault;
|
||||
|
||||
TELE.addData("offset", offset);
|
||||
|
||||
pos -= offset * ((double) 1 / 360);
|
||||
|
||||
if (pos < 0.13) {
|
||||
pos = 0.13;
|
||||
} else if (pos > 0.83) {
|
||||
pos = 0.83;
|
||||
}
|
||||
|
||||
|
||||
targetingSettings = targeting.calculateSettings
|
||||
(robotX,robotY,robotHeading,0.0, turretInterpolate);
|
||||
|
||||
turret.trackGoal(deltaPose);
|
||||
|
||||
//VELOCITY AUTOMATIC
|
||||
if (targetingVel) {
|
||||
vel = targetingSettings.flywheelRPM;
|
||||
@@ -446,105 +426,28 @@ public class TeleopV3 extends LinearOpMode {
|
||||
|
||||
//TODO: test the camera teleop code
|
||||
|
||||
// TODO: TEST THIS CODE
|
||||
|
||||
TELE.addData("posS2", pos);
|
||||
|
||||
LLResult result = robot.limelight.getLatestResult();
|
||||
boolean limelightActive = false;
|
||||
|
||||
double turretMin = 0.13;
|
||||
double turretMax = 0.83;
|
||||
|
||||
if (result != null && result.isValid()) {
|
||||
double tx = result.getTx();
|
||||
double ty = result.getTy();
|
||||
|
||||
if (Math.abs(tx) > limelightDeadband) {
|
||||
limelightActive = true;
|
||||
overrideTurr = true;
|
||||
|
||||
double currentTurretPos = servo.getTurrPos();
|
||||
|
||||
// + tx means tag is right, so rotate right
|
||||
double adjustment = -tx * limelightKp;
|
||||
|
||||
// calculate new position
|
||||
double newTurretPos = currentTurretPos + adjustment;
|
||||
|
||||
if (newTurretPos < turretMin) {
|
||||
double forwardDist = turretMin - newTurretPos;
|
||||
double backwardDist = (currentTurretPos - turretMin) + (turretMax - newTurretPos);
|
||||
// check path distance
|
||||
if (backwardDist < forwardDist && backwardDist < (turretMax - turretMin) / 2) {
|
||||
newTurretPos = turretMax - (turretMin - newTurretPos);
|
||||
} else {
|
||||
newTurretPos = turretMin;
|
||||
}
|
||||
} else if (newTurretPos > turretMax) {
|
||||
double forwardDist = newTurretPos - turretMax;
|
||||
double backwardDist = (turretMax - currentTurretPos) + (newTurretPos - turretMin);
|
||||
if (backwardDist < forwardDist && backwardDist < (turretMax - turretMin) / 2) {
|
||||
newTurretPos = turretMin + (newTurretPos - turretMax);
|
||||
} else {
|
||||
newTurretPos = turretMax;
|
||||
}
|
||||
}
|
||||
|
||||
// Final clamp
|
||||
if (newTurretPos < turretMin) {
|
||||
newTurretPos = turretMin;
|
||||
} else if (newTurretPos > turretMax) {
|
||||
newTurretPos = turretMax;
|
||||
}
|
||||
|
||||
pos = newTurretPos;
|
||||
turretPos = pos;
|
||||
|
||||
camTicker++;
|
||||
TELE.addData("tx", tx);
|
||||
TELE.addData("ty", ty);
|
||||
TELE.addData("limelightAdjustment", adjustment);
|
||||
TELE.addData("limelightActive", true);
|
||||
} else {
|
||||
limelightActive = true;
|
||||
overrideTurr = true;
|
||||
TELE.addData("tx", tx);
|
||||
TELE.addData("ty", ty);
|
||||
TELE.addData("limelightActive", true);
|
||||
TELE.addData("limelightStatus", "Centered");
|
||||
}
|
||||
} else {
|
||||
if (y < 0.3 && y > -0.3 && x < 0.3 && x > -0.3 && rx < 0.3 && rx > -0.3) {
|
||||
TELE.addData("limelightActive", false);
|
||||
TELE.addData("limelightStatus", "No target");
|
||||
} else {
|
||||
camTicker = 0;
|
||||
overrideTurr = false;
|
||||
limelightActive = false;
|
||||
}
|
||||
}
|
||||
|
||||
if (!limelightActive && !overrideTurr) {
|
||||
turretPos = pos;
|
||||
}
|
||||
|
||||
TELE.addData("posS3", turretPos);
|
||||
|
||||
if (manualTurret && !limelightActive) {
|
||||
pos = turrDefault + (manualOffset / 100) + error;
|
||||
}
|
||||
|
||||
if (!overrideTurr && !limelightActive) {
|
||||
turretPos = pos;
|
||||
}
|
||||
|
||||
if (Math.abs(gamepad2.left_stick_x)>0.2 && !limelightActive) {
|
||||
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:
|
||||
|
||||
@@ -729,7 +632,6 @@ public class TeleopV3 extends LinearOpMode {
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
//
|
||||
// if (shootAll) {
|
||||
//
|
||||
@@ -912,6 +814,8 @@ public class TeleopV3 extends LinearOpMode {
|
||||
TELE.addData("hood", robot.hood.getPosition());
|
||||
TELE.addData("targetVel", vel);
|
||||
TELE.addData("Velocity", flywheel.getVelo());
|
||||
TELE.addData("Velo1", flywheel.velo1);
|
||||
TELE.addData("Velo2", flywheel.velo2);
|
||||
TELE.addData("shootOrder", shootOrder);
|
||||
TELE.addData("oddColor", oddBallColor);
|
||||
|
||||
@@ -927,7 +831,7 @@ public class TeleopV3 extends LinearOpMode {
|
||||
TELE.addData("shootall commanded", shootAll);
|
||||
// Targeting Debug
|
||||
TELE.addData("robotX", robotX);
|
||||
TELE.addData( "robotY", robotY);
|
||||
TELE.addData("robotY", robotY);
|
||||
TELE.addData("robotInchesX", targeting.robotInchesX);
|
||||
TELE.addData( "robotInchesY", targeting.robotInchesY);
|
||||
TELE.addData("Targeting Interpolate", turretInterpolate);
|
||||
|
||||
@@ -4,32 +4,35 @@ import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
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.TeleOp;
|
||||
|
||||
import java.util.List;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Turret;
|
||||
|
||||
@Config
|
||||
@TeleOp
|
||||
//TODO: fix to get the apriltag that it is reading
|
||||
public class LimelightTest extends LinearOpMode {
|
||||
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 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
|
||||
public void runOpMode() throws InterruptedException {
|
||||
Limelight3A limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
||||
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();
|
||||
if (isStopRequested()) return;
|
||||
limelight.start();
|
||||
while (opModeIsActive()){
|
||||
if (mode == 0){
|
||||
limelight.pipelineSwitch(pipeline);
|
||||
LLResult result = limelight.getLatestResult();
|
||||
robot.limelight.pipelineSwitch(pipeline);
|
||||
LLResult result = robot.limelight.getLatestResult();
|
||||
if (result != null) {
|
||||
if (result.isValid()) {
|
||||
TELE.addData("tx", result.getTx());
|
||||
@@ -38,40 +41,29 @@ public class LimelightTest extends LinearOpMode {
|
||||
}
|
||||
}
|
||||
} else if (mode == 1){
|
||||
limelight.pipelineSwitch(1);
|
||||
LLResult result = limelight.getLatestResult();
|
||||
if (result != null && result.isValid()) {
|
||||
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||
int id = fiducial.getFiducialId();
|
||||
TELE.addData("ID", id);
|
||||
int obeliskID = turret.detectObelisk();
|
||||
TELE.addData("Limelight ID", obeliskID);
|
||||
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,6 +1,8 @@
|
||||
package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.*;
|
||||
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 com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
@@ -11,28 +13,40 @@ import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utils.Spindexer;
|
||||
|
||||
@Config
|
||||
@TeleOp
|
||||
public class ShooterTest extends LinearOpMode {
|
||||
|
||||
public static int mode = 0;
|
||||
public static int mode = 1;
|
||||
public static double parameter = 0.0;
|
||||
// --- CONSTANTS YOU TUNE ---
|
||||
|
||||
//TODO: @Daniel FIX THE BELOW CONSTANTS A LITTLE IF NEEDED
|
||||
public static double Velocity = 0.0;
|
||||
public static double P = 40.0;
|
||||
public static double I = 0.3;
|
||||
public static double D = 7.0;
|
||||
public static double F = 10.0;
|
||||
public static double P = 255.0;
|
||||
public static double I = 0.0;
|
||||
public static double D = 0.0;
|
||||
public static double F = 7.5;
|
||||
public static double transferPower = 1.0;
|
||||
public static double hoodPos = 0.501;
|
||||
public static double turretPos = 0.501;
|
||||
public static boolean shoot = false;
|
||||
|
||||
public static boolean intake = false;
|
||||
Robot robot;
|
||||
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
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
@@ -40,6 +54,7 @@ public class ShooterTest extends LinearOpMode {
|
||||
DcMotorEx leftShooter = robot.shooter1;
|
||||
DcMotorEx rightShooter = robot.shooter2;
|
||||
flywheel = new Flywheel(hardwareMap);
|
||||
spindexer = new Spindexer(hardwareMap);
|
||||
|
||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
@@ -55,21 +70,65 @@ public class ShooterTest extends LinearOpMode {
|
||||
rightShooter.setPower(parameter);
|
||||
leftShooter.setPower(parameter);
|
||||
} else if (mode == 1) {
|
||||
flywheel.setPIDF(P,I,D,F);
|
||||
flywheel.setPIDF(P, I, D, F);
|
||||
flywheel.manageFlywheel((int) Velocity);
|
||||
}
|
||||
|
||||
if (hoodPos != 0.501) {
|
||||
if (enableHoodAutoOpen) {
|
||||
robot.hood.setPosition(hoodPos+(hoodAdjustFactor*(flywheel.getVelo()/Velocity)));
|
||||
} else {
|
||||
robot.hood.setPosition(hoodPos);
|
||||
}
|
||||
}
|
||||
|
||||
if (intake) {
|
||||
robot.intake.setPower(1);
|
||||
|
||||
} else {
|
||||
robot.intake.setPower(0);
|
||||
}
|
||||
|
||||
|
||||
robot.transfer.setPower(transferPower);
|
||||
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.spin1.setPower(-spinPow);
|
||||
robot.spin2.setPower(spinPow);
|
||||
|
||||
} else {
|
||||
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 1", flywheel.getVelo1());
|
||||
TELE.addData("Velocity 2", flywheel.getVelo2());
|
||||
|
||||
@@ -1,24 +1,20 @@
|
||||
package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Poses.goalPose;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.roadrunner.Pose2d;
|
||||
import com.acmerobotics.roadrunner.Vector2d;
|
||||
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 {
|
||||
public static boolean zeroTurr = false;
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
@@ -27,39 +23,26 @@ public class TurretTest extends LinearOpMode {
|
||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||
);
|
||||
|
||||
AprilTagWebcam webcam = new AprilTagWebcam();
|
||||
webcam.init(robot, TELE);
|
||||
|
||||
Turret turret = new Turret(robot, TELE, webcam);
|
||||
Turret turret = new Turret(robot, TELE, robot.limelight);
|
||||
waitForStart();
|
||||
|
||||
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(10, 0,0));
|
||||
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(15, 0,0));
|
||||
|
||||
while(opModeIsActive()){
|
||||
|
||||
drive.updatePoseEstimate();
|
||||
Pose2d robotPose = drive.localizer.getPose();
|
||||
turret.trackGoal(drive.localizer.getPose());
|
||||
|
||||
double dx = goalPose.position.x - robotPose.position.x;
|
||||
double dy = goalPose.position.y - robotPose.position.y;
|
||||
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());
|
||||
|
||||
double heading = robotPose.heading.toDouble();
|
||||
if(zeroTurr){
|
||||
turret.zeroTurretEncoder();
|
||||
}
|
||||
|
||||
// field vector -> robot frame... avoids double calculation
|
||||
double relX = dx * Math.cos(-heading) - dy * Math.sin(-heading);
|
||||
double relY = dx * Math.sin(-heading) + dy * Math.cos(-heading);
|
||||
|
||||
Pose2d deltaPos = new Pose2d(
|
||||
new Vector2d(relX, relY),
|
||||
robotPose.heading
|
||||
);
|
||||
|
||||
|
||||
turret.trackGoal(deltaPos);
|
||||
|
||||
TELE.addData("Robot Pose", robotPose);
|
||||
TELE.addData("Goal Pose", goalPose);
|
||||
TELE.addData("Delta Pos", deltaPos);
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
|
||||
@@ -9,8 +9,8 @@ public class Flywheel {
|
||||
Robot robot;
|
||||
public PIDFCoefficients shooterPIDF1, shooterPIDF2;
|
||||
double velo = 0.0;
|
||||
double velo1 = 0.0;
|
||||
double velo2 = 0.0;
|
||||
public double velo1 = 0.0;
|
||||
public double velo2 = 0.0;
|
||||
double targetVelocity = 0.0;
|
||||
double powPID = 0.0;
|
||||
boolean steady = false;
|
||||
@@ -38,10 +38,14 @@ public class Flywheel {
|
||||
|
||||
// Set the robot PIDF for the next cycle.
|
||||
public void setPIDF(double p, double i, double d, double f) {
|
||||
robot.shooterPIDF.p = p;
|
||||
robot.shooterPIDF.i = i;
|
||||
robot.shooterPIDF.d = d;
|
||||
robot.shooterPIDF.f = f;
|
||||
shooterPIDF1.p = p;
|
||||
shooterPIDF1.i = i;
|
||||
shooterPIDF1.d = d;
|
||||
shooterPIDF1.f = f;
|
||||
shooterPIDF2.p = p;
|
||||
shooterPIDF2.i = i;
|
||||
shooterPIDF2.d = d;
|
||||
shooterPIDF2.f = f;
|
||||
}
|
||||
|
||||
// Convert from RPM to Ticks per Second
|
||||
@@ -54,10 +58,6 @@ public class Flywheel {
|
||||
targetVelocity = commandedVelocity;
|
||||
|
||||
// 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.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
||||
|
||||
@@ -8,6 +8,8 @@ import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||
|
||||
@TeleOp
|
||||
@Config
|
||||
public class PositionalServoProgrammer extends LinearOpMode {
|
||||
@@ -25,11 +27,17 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
||||
public static double hoodPos = 0.501;
|
||||
public static int mode = 0; //0 for positional, 1 for power
|
||||
|
||||
Turret turret;
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
robot = new Robot(hardwareMap);
|
||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||
servo = new Servos(hardwareMap);
|
||||
|
||||
|
||||
|
||||
turret = new Turret(robot, TELE, robot.limelight );
|
||||
waitForStart();
|
||||
if (isStopRequested()) return;
|
||||
while (opModeIsActive()){
|
||||
@@ -66,12 +74,13 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
||||
//TODO: @KeshavAnandCode do the above please
|
||||
|
||||
TELE.addData("spindexer pos", servo.getSpinPos());
|
||||
TELE.addData("turret pos", servo.getTurrPos());
|
||||
TELE.addData("turret pos", robot.turr1.getPosition());
|
||||
TELE.addData("spindexer voltage 1", robot.spin1Pos.getVoltage());
|
||||
TELE.addData("spindexer voltage 2", robot.spin2Pos.getVoltage());
|
||||
TELE.addData("hood pos", robot.hood.getPosition());
|
||||
TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage());
|
||||
TELE.addData("spindexer pow", robot.spin1.getPower());
|
||||
TELE.addData("tpos ", turret.getTurrPos() );
|
||||
TELE.update();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -20,8 +20,8 @@ public class Robot {
|
||||
|
||||
//Initialize Public Components
|
||||
|
||||
public static boolean usingLimelight = false;
|
||||
public static boolean usingCamera = true;
|
||||
public static boolean usingLimelight = true;
|
||||
public static boolean usingCamera = false;
|
||||
public DcMotorEx frontLeft;
|
||||
public DcMotorEx frontRight;
|
||||
public DcMotorEx backLeft;
|
||||
@@ -29,10 +29,10 @@ public class Robot {
|
||||
public DcMotorEx intake;
|
||||
public DcMotorEx transfer;
|
||||
public PIDFCoefficients shooterPIDF;
|
||||
public double shooterPIDF_P = 10.0;
|
||||
public double shooterPIDF_I = 0.6;
|
||||
public double shooterPIDF_D = 5.0;
|
||||
public double shooterPIDF_F = 10.0;
|
||||
public double shooterPIDF_P = 255.0;
|
||||
public double shooterPIDF_I = 0.0;
|
||||
public double shooterPIDF_D = 0.0;
|
||||
public double shooterPIDF_F = 7.5;
|
||||
public double[] shooterPIDF_StepSizes = {10.0, 1.0, 0.001, 0.0001};
|
||||
public DcMotorEx shooter1;
|
||||
public DcMotorEx shooter2;
|
||||
@@ -79,8 +79,10 @@ public class Robot {
|
||||
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(0);
|
||||
shooter2.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
||||
shooter2.setVelocity(0);
|
||||
|
||||
hood = hardwareMap.get(Servo.class, "hood");
|
||||
|
||||
|
||||
@@ -8,7 +8,7 @@ import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
public class Servos {
|
||||
//PID 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 spin_scalar = 1.0086;
|
||||
public static double spin_restPos = 0.0;
|
||||
@@ -40,7 +40,7 @@ public class Servos {
|
||||
}
|
||||
|
||||
public boolean spinEqual(double pos) {
|
||||
return Math.abs(pos - this.getSpinPos()) < 0.02;
|
||||
return Math.abs(pos - this.getSpinPos()) < 0.03;
|
||||
}
|
||||
|
||||
public double getTurrPos() {
|
||||
|
||||
@@ -16,9 +16,11 @@ import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
|
||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinP;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.constants.Types;
|
||||
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||
|
||||
public class Spindexer {
|
||||
|
||||
Robot robot;
|
||||
Servos servos;
|
||||
Flywheel flywheel;
|
||||
@@ -36,6 +38,7 @@ public class Spindexer {
|
||||
public double distanceFrontDriver = 0.0;
|
||||
public double distanceFrontPassenger = 0.0;
|
||||
|
||||
public Types.Motif desiredMotif = Types.Motif.NONE;
|
||||
// For Use
|
||||
enum RotatedBallPositionNames {
|
||||
REARCENTER,
|
||||
@@ -62,6 +65,8 @@ public class Spindexer {
|
||||
SHOOTNEXT,
|
||||
SHOOTMOVING,
|
||||
SHOOTWAIT,
|
||||
SHOOT_ALL_PREP,
|
||||
SHOOT_ALL_READY
|
||||
};
|
||||
|
||||
public IntakeState currentIntakeState = IntakeState.UNKNOWN_START;
|
||||
@@ -272,7 +277,6 @@ public class Spindexer {
|
||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.UNKNOWN_DETECT;
|
||||
stopSpindexer();
|
||||
detectBalls(true, true);
|
||||
unknownColorDetect = 0;
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
@@ -283,7 +287,7 @@ public class Spindexer {
|
||||
if (unknownColorDetect >5) {
|
||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||
} else {
|
||||
detectBalls(true, true);
|
||||
//detectBalls(true, true);
|
||||
unknownColorDetect++;
|
||||
}
|
||||
break;
|
||||
@@ -327,6 +331,7 @@ public class Spindexer {
|
||||
}
|
||||
if (currentIntakeState != Spindexer.IntakeState.MOVING) {
|
||||
// Full
|
||||
commandedIntakePosition = bestFitMotif();
|
||||
currentIntakeState = Spindexer.IntakeState.FULL;
|
||||
}
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
@@ -337,7 +342,7 @@ public class Spindexer {
|
||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.INTAKE;
|
||||
stopSpindexer();
|
||||
detectBalls(false, false);
|
||||
//detectBalls(false, false);
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
@@ -355,6 +360,28 @@ public class Spindexer {
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
break;
|
||||
|
||||
case SHOOT_ALL_PREP:
|
||||
// We get here with function call to prepareToShootMotif
|
||||
// Stopping when we get to the new position
|
||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.SHOOT_ALL_READY;
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
||||
}
|
||||
break;
|
||||
|
||||
case SHOOT_ALL_READY:
|
||||
// Double Check Colors
|
||||
//detectBalls(false, false); // Minimize hardware calls
|
||||
if (ballPositions[0].isEmpty && ballPositions[1].isEmpty && ballPositions[2].isEmpty) {
|
||||
// All ball shot move to intake state
|
||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||
}
|
||||
// Maintain Position
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
break;
|
||||
|
||||
case SHOOTNEXT:
|
||||
// Find Next Open Position and start movement
|
||||
if (!ballPositions[0].isEmpty) {
|
||||
@@ -383,16 +410,6 @@ public class Spindexer {
|
||||
// Stopping when we get to the new position
|
||||
if (servos.spinEqual(outakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.SHOOTWAIT;
|
||||
ballPositions[commandedIntakePosition].isEmpty = true;
|
||||
// Advance to next full position and wait
|
||||
// commandedIntakePosition++;
|
||||
// if (commandedIntakePosition > 2) {
|
||||
// commandedIntakePosition = 0;
|
||||
// }
|
||||
// // Continue moving to next position
|
||||
// servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||
// currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
||||
@@ -404,7 +421,7 @@ public class Spindexer {
|
||||
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||
currentIntakeState = Spindexer.IntakeState.INTAKE;
|
||||
stopSpindexer();
|
||||
detectBalls(true, false);
|
||||
//detectBalls(true, false);
|
||||
} else {
|
||||
// Keep moving the spindexer
|
||||
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||
@@ -420,6 +437,55 @@ public class Spindexer {
|
||||
return false;
|
||||
}
|
||||
|
||||
public void setDesiredMotif (Types.Motif newMotif) {
|
||||
desiredMotif = newMotif;
|
||||
}
|
||||
|
||||
// Returns the best fit for the motiff
|
||||
public int bestFitMotif () {
|
||||
switch (desiredMotif) {
|
||||
case GPP:
|
||||
if (ballPositions[0].ballColor == BallColor.GREEN) {
|
||||
return 2;
|
||||
} else if (ballPositions[1].ballColor == BallColor.GREEN) {
|
||||
return 0;
|
||||
} else {
|
||||
return 1;
|
||||
}
|
||||
//break;
|
||||
case PGP:
|
||||
if (ballPositions[0].ballColor == BallColor.GREEN) {
|
||||
return 0;
|
||||
} else if (ballPositions[1].ballColor == BallColor.GREEN) {
|
||||
return 1;
|
||||
} else {
|
||||
return 3;
|
||||
}
|
||||
//break;
|
||||
case PPG:
|
||||
if (ballPositions[0].ballColor == BallColor.GREEN) {
|
||||
return 1;
|
||||
} else if (ballPositions[1].ballColor == BallColor.GREEN) {
|
||||
return 0;
|
||||
} else {
|
||||
return 2;
|
||||
}
|
||||
//break;
|
||||
case NONE:
|
||||
return 0;
|
||||
//break;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
void prepareToShootMotif () {
|
||||
commandedIntakePosition = bestFitMotif();
|
||||
}
|
||||
|
||||
void shootAllToIntake () {
|
||||
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||
}
|
||||
|
||||
public void update()
|
||||
{
|
||||
}
|
||||
|
||||
@@ -9,8 +9,8 @@ import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
public class Targeting {
|
||||
MultipleTelemetry TELE;
|
||||
|
||||
double cancelOffsetX = 7.071067811;
|
||||
double cancelOffsetY = 7.071067811;
|
||||
double cancelOffsetX = 0.0; // was -40.0
|
||||
double cancelOffsetY = 0.0; // was 7.0
|
||||
double unitConversionFactor = 0.95;
|
||||
|
||||
int tileSize = 24; //inches
|
||||
@@ -37,33 +37,33 @@ public class Targeting {
|
||||
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);
|
||||
KNOWNTARGETING[0][0] = new Settings (2300.0, 0.93);
|
||||
KNOWNTARGETING[0][1] = new Settings (2300.0, 0.93);
|
||||
KNOWNTARGETING[0][2] = new Settings (2500.0, 0.78);
|
||||
KNOWNTARGETING[0][3] = new Settings (2800.0, 0.68);
|
||||
KNOWNTARGETING[0][4] = new Settings (3000.0, 0.58);
|
||||
KNOWNTARGETING[0][5] = new Settings (3000.0, 0.58);
|
||||
// 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);
|
||||
KNOWNTARGETING[1][0] = new Settings (2300.0, 0.93);
|
||||
KNOWNTARGETING[1][1] = new Settings (2300.0, 0.93);
|
||||
KNOWNTARGETING[1][2] = new Settings (2600.0, 0.78);
|
||||
KNOWNTARGETING[1][3] = new Settings (2800.0, 0.62);
|
||||
KNOWNTARGETING[1][4] = new Settings (3000.0, 0.55);
|
||||
KNOWNTARGETING[1][5] = new Settings (3200.0, 0.50);
|
||||
// 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);
|
||||
KNOWNTARGETING[2][0] = new Settings (2500.0, 0.78);
|
||||
KNOWNTARGETING[2][1] = new Settings (2500.0, 0.78);
|
||||
KNOWNTARGETING[2][2] = new Settings (2700.0, 0.60);
|
||||
KNOWNTARGETING[2][3] = new Settings (2900.0, 0.53);
|
||||
KNOWNTARGETING[2][4] = new Settings (3100.0, 0.50);
|
||||
KNOWNTARGETING[2][5] = new Settings (3100.0, 0.50);
|
||||
// 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);
|
||||
KNOWNTARGETING[3][0] = new Settings (2900.0, 0.50);
|
||||
KNOWNTARGETING[3][1] = new Settings (2900.0, 0.50);
|
||||
KNOWNTARGETING[3][2] = new Settings (2900.0, 0.50);
|
||||
KNOWNTARGETING[3][3] = new Settings (3100.0, 0.47);
|
||||
KNOWNTARGETING[3][4] = new Settings (3100.0, 0.47);
|
||||
KNOWNTARGETING[3][5] = new Settings (3100.0, 0.47);
|
||||
// ROW 4
|
||||
KNOWNTARGETING[4][0] = new Settings (4540.0, 0.1);
|
||||
KNOWNTARGETING[4][1] = new Settings (4541.0, 0.1);
|
||||
@@ -89,16 +89,16 @@ public class Targeting {
|
||||
|
||||
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;
|
||||
double rotatedY = (robotX + cancelOffsetX) * sin45 + (robotY + cancelOffsetY) * cos45;
|
||||
double rotatedX = (robotX + cancelOffsetX) * cos45 - (robotY + cancelOffsetY) * sin45;
|
||||
|
||||
// Convert robot coordinates to inches
|
||||
robotInchesX = rotatedX * unitConversionFactor;
|
||||
robotInchesY = rotatedY * unitConversionFactor;
|
||||
|
||||
// Find approximate location in the grid
|
||||
robotGridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) + 1);
|
||||
robotGridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
|
||||
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));
|
||||
@@ -107,8 +107,8 @@ public class Targeting {
|
||||
// basic search
|
||||
if(!interpolate) {
|
||||
if ((robotGridY < 6) && (robotGridX <6)) {
|
||||
recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridY][robotGridX].flywheelRPM;
|
||||
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridY][robotGridX].hoodAngle;
|
||||
recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridX][robotGridY].flywheelRPM;
|
||||
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridX][robotGridY].hoodAngle;
|
||||
}
|
||||
return recommendedSettings;
|
||||
} else {
|
||||
|
||||
@@ -1,3 +1,4 @@
|
||||
|
||||
package org.firstinspires.ftc.teamcode.utils;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||
@@ -5,61 +6,140 @@ 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 com.qualcomm.robotcore.util.Range;
|
||||
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||
import com.qualcomm.hardware.limelightvision.LLResult;
|
||||
import com.qualcomm.hardware.limelightvision.LLResultTypes;
|
||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
|
||||
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.Pose3D;
|
||||
|
||||
import java.util.List;
|
||||
|
||||
@Config
|
||||
public class Turret {
|
||||
|
||||
public static double turretTolerance = 0.02;
|
||||
public static double turrPosScalar = 0.00011264432;
|
||||
public static double turret180Range = 0.4;
|
||||
public static double turrDefault = 0.4;
|
||||
public static double turretRange = 0.6;
|
||||
// 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 turrMin = 0.2;
|
||||
public static double turrMax = 0.8;
|
||||
|
||||
public static double turretTolerance = 0.02;
|
||||
|
||||
public static double cameraBearingEqual = 1.5;
|
||||
public static double errorLearningRate = 0.02; // must be low
|
||||
public static double maxOffsetDeg = 30.0;
|
||||
|
||||
private final Robot robot;
|
||||
private final MultipleTelemetry TELE;
|
||||
private final AprilTagWebcam webcam;
|
||||
|
||||
public static double mult = 0.0;
|
||||
private boolean lockOffset = false;
|
||||
Robot robot;
|
||||
MultipleTelemetry TELE;
|
||||
Limelight3A webcam;
|
||||
private int obeliskID = 0;
|
||||
private double offsetDeg = 0.0;
|
||||
private double offset = 0.0;
|
||||
|
||||
public Turret(Robot rob, MultipleTelemetry tele, AprilTagWebcam cam) {
|
||||
this.robot = rob;
|
||||
private PIDFController controller = new PIDFController(kP, kI, kD, kF);
|
||||
double tx = 0.0;
|
||||
double ty = 0.0;
|
||||
double limelightPosX = 0.0;
|
||||
double limelightPosY = 0.0;
|
||||
public static double clampTolerance = 0.03;
|
||||
|
||||
public Turret(Robot rob, MultipleTelemetry tele, Limelight3A cam) {
|
||||
this.TELE = tele;
|
||||
this.robot = rob;
|
||||
this.webcam = cam;
|
||||
webcam.start();
|
||||
if (redAlliance){
|
||||
webcam.pipelineSwitch(3);
|
||||
} else {
|
||||
webcam.pipelineSwitch(2);
|
||||
}
|
||||
}
|
||||
|
||||
public double getTurretPos() {
|
||||
return robot.turr1Pos.getVoltage() / 3.3;
|
||||
public void zeroTurretEncoder() {
|
||||
robot.intake.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||
robot.intake.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||
}
|
||||
|
||||
public void manualSetTurret(double pos) {
|
||||
pos = Range.clip(pos, turrMin, turrMax);
|
||||
public double getTurrPos() {
|
||||
return turrPosScalar * (robot.turr1Pos.getVoltage() / 3.3) + turrDefault;
|
||||
|
||||
}
|
||||
|
||||
public void manualSetTurret(double pos){
|
||||
robot.turr1.setPosition(pos);
|
||||
robot.turr2.setPosition(1.0 - pos);
|
||||
robot.turr2.setPosition(1-pos);
|
||||
}
|
||||
|
||||
public boolean turretAt(double pos) {
|
||||
return Math.abs(pos - getTurretPos()) < turretTolerance;
|
||||
public boolean turretEqual(double pos) {
|
||||
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
|
||||
}
|
||||
|
||||
public double getBearingDeg() {
|
||||
AprilTagDetection tag =
|
||||
redAlliance ? webcam.getTagById(24) : webcam.getTagById(20);
|
||||
return (tag != null) ? tag.ftcPose.bearing : Double.NaN;
|
||||
private void limelightRead(){ // only for tracking purposes, not general reads
|
||||
if (redAlliance){
|
||||
webcam.pipelineSwitch(3);
|
||||
} else {
|
||||
webcam.pipelineSwitch(2);
|
||||
}
|
||||
|
||||
LLResult result = webcam.getLatestResult();
|
||||
if (result != null) {
|
||||
if (result.isValid()) {
|
||||
tx = result.getTx();
|
||||
ty = result.getTy();
|
||||
// MegaTag1 code for receiving position
|
||||
Pose3D botpose = result.getBotpose();
|
||||
if (botpose != null){
|
||||
limelightPosX = botpose.getPosition().x;
|
||||
limelightPosY = botpose.getPosition().y;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public double getBearing() {
|
||||
tx = 1000;
|
||||
limelightRead();
|
||||
return tx;
|
||||
}
|
||||
|
||||
public double getTy(){
|
||||
limelightRead();
|
||||
return ty;
|
||||
}
|
||||
|
||||
public double getLimelightX(){
|
||||
limelightRead();
|
||||
return limelightPosX;
|
||||
}
|
||||
|
||||
public double getLimelightY(){
|
||||
limelightRead();
|
||||
return limelightPosY;
|
||||
}
|
||||
|
||||
public int detectObelisk() {
|
||||
if (webcam.getTagById(21) != null) obeliskID = 21;
|
||||
else if (webcam.getTagById(22) != null) obeliskID = 22;
|
||||
else if (webcam.getTagById(23) != null) obeliskID = 23;
|
||||
webcam.pipelineSwitch(1);
|
||||
LLResult result = webcam.getLatestResult();
|
||||
if (result != null && result.isValid()) {
|
||||
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
|
||||
for (LLResultTypes.FiducialResult fiducial : fiducials) {
|
||||
obeliskID = fiducial.getFiducialId();
|
||||
}
|
||||
}
|
||||
return obeliskID;
|
||||
}
|
||||
|
||||
@@ -67,34 +147,81 @@ public class Turret {
|
||||
return obeliskID;
|
||||
}
|
||||
|
||||
public void zeroOffset() {
|
||||
offset = 0.0;
|
||||
}
|
||||
|
||||
public void lockOffset(boolean lock) {
|
||||
lockOffset = lock;
|
||||
}
|
||||
|
||||
/*
|
||||
Param @deltaPos = Pose2d when subtracting robot x, y, heading from goal x, y, heading
|
||||
*/
|
||||
public void trackGoal(Pose2d deltaPos) {
|
||||
|
||||
double turretAngleDeg = Math.toDegrees(
|
||||
controller.setPIDF(kP, kI, kD, kF);
|
||||
/* ---------------- FIELD → TURRET GEOMETRY ---------------- */
|
||||
|
||||
// Angle from robot to goal in robot frame
|
||||
double desiredTurretAngleDeg = Math.toDegrees(
|
||||
Math.atan2(deltaPos.position.y, deltaPos.position.x)
|
||||
);
|
||||
|
||||
double bearingDeg = getBearingDeg();
|
||||
// Robot heading (field → robot)
|
||||
double robotHeadingDeg = Math.toDegrees(deltaPos.heading.toDouble());
|
||||
|
||||
if (!Double.isNaN(bearingDeg) &&
|
||||
Math.abs(bearingDeg) < cameraBearingEqual) {
|
||||
// Turret angle needed relative to robot
|
||||
double turretAngleDeg = desiredTurretAngleDeg - robotHeadingDeg;
|
||||
|
||||
offsetDeg -= bearingDeg * errorLearningRate;
|
||||
offsetDeg = Range.clip(offsetDeg, -maxOffsetDeg, maxOffsetDeg);
|
||||
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
|
||||
|
||||
turretAngleDeg += offset;
|
||||
|
||||
/* ---------------- ANGLE → SERVO ---------------- */
|
||||
|
||||
double turretPos = turrDefault + (turretAngleDeg * (turret180Range * 2.0) / 360);
|
||||
|
||||
// Clamp to servo range
|
||||
double currentEncoderPos = this.getTurrPos();
|
||||
|
||||
if (!turretEqual(turretPos)) {
|
||||
double diff = turretPos - currentEncoderPos;
|
||||
turretPos = turretPos + diff * mult;
|
||||
}
|
||||
|
||||
turretAngleDeg += offsetDeg;
|
||||
if (currentEncoderPos < (turrMin + clampTolerance) || currentEncoderPos > (turrMax - clampTolerance)) {
|
||||
// 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
|
||||
|
||||
double turretPos =
|
||||
turrDefault + (turretAngleDeg / 180.0) * turretRange;
|
||||
// Proportional: respond to current error
|
||||
|
||||
turretPos = Range.clip(turretPos, turrMin, turrMax);
|
||||
offset = -controller.calculate(tagBearingDeg);
|
||||
|
||||
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
robot.turr1.setPosition(turretPos);
|
||||
robot.turr2.setPosition(1.0 - turretPos);
|
||||
|
||||
TELE.addData("Turret Angle (deg)", turretAngleDeg);
|
||||
TELE.addData("Offset (deg)", offsetDeg);
|
||||
TELE.addData("Tag Bearing (deg)", bearingDeg);
|
||||
TELE.addData("Turret Servo", turretPos);
|
||||
/* ---------------- TELEMETRY ---------------- */
|
||||
|
||||
TELE.addData("Turret Angle", turretAngleDeg);
|
||||
TELE.addData("Bearing", tagBearingDeg);
|
||||
TELE.addData("Offset", offset);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -25,5 +25,9 @@ allprojects {
|
||||
}
|
||||
|
||||
repositories {
|
||||
repositories {
|
||||
mavenCentral()
|
||||
google()
|
||||
maven { url 'https://maven.pedropathing.com' }
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user