Compare commits
29 Commits
d42af20447
...
Targeting
| Author | SHA1 | Date | |
|---|---|---|---|
| 4050a354f7 | |||
| f20e640c62 | |||
| c2e9d8fa87 | |||
| 46a5366a4a | |||
| fbdeb6e291 | |||
|
|
298b7bca8c | ||
| 2f0fcad128 | |||
| 45199b952b | |||
| 76ceb91fb7 | |||
| daccec4fdd | |||
| b55d44ae97 | |||
| 50212015e3 | |||
| c271c88e45 | |||
| 33300876ef | |||
| e1745500cc | |||
| 0dbf155608 | |||
| 313eeeaa95 | |||
| b28647373a | |||
| 7e7254aaea | |||
| e7dfa11196 | |||
| a3068cea2e | |||
| 51bf55cc49 | |||
| 6f3a178a08 | |||
| ccb52f625d | |||
| 8f92dc8f31 | |||
| 40d51ce757 | |||
| cfd09df8a0 | |||
| f1d4bb9d24 | |||
| 59796154bd |
@@ -76,7 +76,7 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|||||||
|
|
||||||
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.FlywheelV2;
|
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;
|
||||||
|
|
||||||
@@ -93,7 +93,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
MecanumDrive drive;
|
MecanumDrive drive;
|
||||||
FlywheelV2 flywheel;
|
Flywheel flywheel;
|
||||||
Servos servo;
|
Servos servo;
|
||||||
double velo = 0.0;
|
double velo = 0.0;
|
||||||
boolean gpp = false;
|
boolean gpp = false;
|
||||||
@@ -109,10 +109,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
public Action initShooter(int vel) {
|
public Action initShooter(int vel) {
|
||||||
return new Action() {
|
return new Action() {
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
flywheel.manageFlywheel(vel);
|
||||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
velo = flywheel.getVelo();
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
TELE.addData("Velocity", velo);
|
TELE.addData("Velocity", velo);
|
||||||
TELE.update();
|
TELE.update();
|
||||||
@@ -180,10 +178,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
@Override
|
@Override
|
||||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
flywheel.manageFlywheel(vel);
|
||||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
velo = flywheel.getVelo();
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
spinPID = servo.setSpinPos(spindexer);
|
spinPID = servo.setSpinPos(spindexer);
|
||||||
robot.spin1.setPower(spinPID);
|
robot.spin1.setPower(spinPID);
|
||||||
@@ -224,10 +220,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
TELE.addLine("shooting");
|
TELE.addLine("shooting");
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
flywheel.manageFlywheel(vel);
|
||||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
velo = flywheel.getVelo();
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
@@ -376,10 +370,8 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
ticker++;
|
ticker++;
|
||||||
|
|
||||||
powPID = flywheel.manageFlywheel(vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
flywheel.manageFlywheel(vel);
|
||||||
velo = flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
velo = flywheel.getVelo();
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
double s1D = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
double s2D = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
@@ -454,7 +446,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
|
|
||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
|
|
||||||
flywheel = new FlywheelV2();
|
flywheel = new Flywheel(hardwareMap);
|
||||||
|
|
||||||
TELE = new MultipleTelemetry(
|
TELE = new MultipleTelemetry(
|
||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
@@ -718,7 +710,7 @@ public class ProtoAutoClose_V3 extends LinearOpMode {
|
|||||||
bearing = result.getTx();
|
bearing = result.getTx();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
double turretPos = robot.turr1Pos.getCurrentPosition() - (bearing / 1300);
|
double turretPos = (bearing / 1300);
|
||||||
robot.turr1.setPosition(turretPos);
|
robot.turr1.setPosition(turretPos);
|
||||||
robot.turr2.setPosition(1 - turretPos);
|
robot.turr2.setPosition(1 - turretPos);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -12,7 +12,7 @@ public class Poses {
|
|||||||
|
|
||||||
public static double relativeGoalHeight = goalHeight - turretHeight;
|
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 rx1 = 40, ry1 = -7, rh1 = 0;
|
||||||
public static double rx2a = 41, ry2a = 18, rh2a = Math.toRadians(140);
|
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 bx4b = 48, by4b = -79, bh4b = Math.toRadians(-140);
|
||||||
public static double rfx1 = 10, rfy1 = 0, rfh1 = 0; //TODO: test this
|
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
|
@Config
|
||||||
public class ServoPositions {
|
public class ServoPositions {
|
||||||
|
|
||||||
public static double spindexer_intakePos1 = 0.39;
|
public static double spindexer_intakePos1 = 0.19;
|
||||||
|
|
||||||
public static double spindexer_intakePos2 = 0.5;
|
public static double spindexer_intakePos2 = 0.35;//0.5;
|
||||||
|
|
||||||
public static double spindexer_intakePos3 = 0.66;
|
public static double spindexer_intakePos3 = 0.51;//0.66;
|
||||||
|
|
||||||
public static double spindexer_outtakeBall3 = 0.47;
|
public static double spindexer_outtakeBall3 = 0.47;
|
||||||
|
|
||||||
@@ -42,4 +42,8 @@ public class ServoPositions {
|
|||||||
public static double turret_detectBlueClose = 0.6;
|
public static double turret_detectBlueClose = 0.6;
|
||||||
public static double turrDefault = 0.4;
|
public static double turrDefault = 0.4;
|
||||||
|
|
||||||
|
public static double turrMin = 0.2;
|
||||||
|
public static double turrMax = 0.8;
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -129,7 +129,7 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
);
|
);
|
||||||
servo = new Servos(hardwareMap);
|
servo = new Servos(hardwareMap);
|
||||||
flywheel = new Flywheel();
|
flywheel = new Flywheel(hardwareMap);
|
||||||
|
|
||||||
drive = new MecanumDrive(hardwareMap, teleStart);
|
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||||
|
|
||||||
@@ -282,10 +282,7 @@ public class TeleopV2 extends LinearOpMode {
|
|||||||
|
|
||||||
//SHOOTER:
|
//SHOOTER:
|
||||||
|
|
||||||
double powPID = flywheel.manageFlywheel((int) vel, robot.shooter1.getCurrentPosition());
|
double powPID = flywheel.manageFlywheel((int) vel);
|
||||||
|
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
robot.transfer.setPower(1);
|
robot.transfer.setPower(1);
|
||||||
|
|
||||||
|
|||||||
@@ -1,11 +1,9 @@
|
|||||||
package org.firstinspires.ftc.teamcode.teleop;
|
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.Poses.teleStart;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
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;
|
||||||
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.spinD;
|
||||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinF;
|
import static org.firstinspires.ftc.teamcode.utils.Servos.spinF;
|
||||||
import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
|
import static org.firstinspires.ftc.teamcode.utils.Servos.spinI;
|
||||||
@@ -21,7 +19,6 @@ import com.acmerobotics.roadrunner.TranslationalVelConstraint;
|
|||||||
import com.acmerobotics.roadrunner.Vector2d;
|
import com.acmerobotics.roadrunner.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.LLResult;
|
|
||||||
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;
|
||||||
@@ -29,9 +26,13 @@ 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.FlywheelV2;
|
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Servos;
|
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.ArrayList;
|
||||||
import java.util.List;
|
import java.util.List;
|
||||||
@@ -52,6 +53,8 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
public static boolean manualTurret = true;
|
public static boolean manualTurret = true;
|
||||||
public double vel = 3000;
|
public double vel = 3000;
|
||||||
public boolean autoVel = true;
|
public boolean autoVel = true;
|
||||||
|
public boolean targetingVel = true;
|
||||||
|
public boolean targetingHood = true;
|
||||||
public double manualOffset = 0.0;
|
public double manualOffset = 0.0;
|
||||||
public boolean autoHood = true;
|
public boolean autoHood = true;
|
||||||
public boolean green1 = false;
|
public boolean green1 = false;
|
||||||
@@ -68,8 +71,11 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
MultipleTelemetry TELE;
|
||||||
Servos servo;
|
Servos servo;
|
||||||
FlywheelV2 flywheel;
|
Flywheel flywheel;
|
||||||
MecanumDrive drive;
|
MecanumDrive drive;
|
||||||
|
Spindexer spindexer;
|
||||||
|
Targeting targeting;
|
||||||
|
Targeting.Settings targetingSettings;
|
||||||
double autoHoodOffset = 0.0;
|
double autoHoodOffset = 0.0;
|
||||||
|
|
||||||
int shooterTicker = 0;
|
int shooterTicker = 0;
|
||||||
@@ -94,7 +100,8 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
boolean shootA = true;
|
boolean shootA = true;
|
||||||
boolean shootB = true;
|
boolean shootB = true;
|
||||||
boolean shootC = true;
|
boolean shootC = true;
|
||||||
boolean autoSpintake = true;
|
boolean autoSpintake = false;
|
||||||
|
boolean enableSpindexerManager = true;
|
||||||
List<Integer> shootOrder = new ArrayList<>();
|
List<Integer> shootOrder = new ArrayList<>();
|
||||||
boolean outtake1 = false;
|
boolean outtake1 = false;
|
||||||
boolean outtake2 = false;
|
boolean outtake2 = false;
|
||||||
@@ -113,6 +120,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
private double transferStamp = 0.0;
|
private double transferStamp = 0.0;
|
||||||
private int tickerA = 1;
|
private int tickerA = 1;
|
||||||
private boolean transferIn = false;
|
private boolean transferIn = false;
|
||||||
|
boolean turretInterpolate = false;
|
||||||
|
|
||||||
public static double velPrediction(double distance) {
|
public static double velPrediction(double distance) {
|
||||||
if (distance < 30) {
|
if (distance < 30) {
|
||||||
@@ -140,20 +148,29 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
servo = new Servos(hardwareMap);
|
servo = new Servos(hardwareMap);
|
||||||
flywheel = new FlywheelV2();
|
flywheel = new Flywheel(hardwareMap);
|
||||||
drive = new MecanumDrive(hardwareMap, teleStart);
|
drive = new MecanumDrive(hardwareMap, teleStart);
|
||||||
|
spindexer = new Spindexer(hardwareMap);
|
||||||
|
targeting = new Targeting();
|
||||||
|
targetingSettings = new Targeting.Settings(0.0, 0.0);
|
||||||
|
|
||||||
PIDFController tController = new PIDFController(tp, ti, td, tf);
|
PIDFController tController = new PIDFController(tp, ti, td, tf);
|
||||||
|
|
||||||
tController.setTolerance(0.001);
|
tController.setTolerance(0.001);
|
||||||
|
//
|
||||||
|
// if (redAlliance) {
|
||||||
|
// robot.limelight.pipelineSwitch(3);
|
||||||
|
// } else {
|
||||||
|
// robot.limelight.pipelineSwitch(2);
|
||||||
|
// }
|
||||||
|
|
||||||
if (redAlliance) {
|
// robot.limelight.start();
|
||||||
robot.limelight.pipelineSwitch(3);
|
|
||||||
} else {
|
|
||||||
robot.limelight.pipelineSwitch(2);
|
|
||||||
}
|
|
||||||
|
|
||||||
robot.limelight.start();
|
AprilTagWebcam webcam = new AprilTagWebcam();
|
||||||
|
webcam.init(robot, TELE);
|
||||||
|
|
||||||
|
Turret turret = new Turret(robot, TELE, webcam);
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
waitForStart();
|
waitForStart();
|
||||||
if (isStopRequested()) return;
|
if (isStopRequested()) return;
|
||||||
@@ -368,46 +385,26 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
double robotY = robY - yOffset;
|
double robotY = robY - yOffset;
|
||||||
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
double robotHeading = drive.localizer.getPose().heading.toDouble();
|
||||||
|
|
||||||
double goalX = -10;
|
double goalX = -15;
|
||||||
double goalY = 0;
|
double goalY = 0;
|
||||||
|
|
||||||
double dx = goalX - robotX; // delta x from robot to goal
|
double dx = robotX - goalX; // delta x from robot to goal
|
||||||
double dy = goalY - robotY; // delta y 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);
|
double distanceToGoal = Math.sqrt(dx * dx + dy * dy);
|
||||||
|
|
||||||
desiredTurretAngle = (Math.toDegrees(Math.atan2(dy, dx)) + 360) % 360;
|
targetingSettings = targeting.calculateSettings
|
||||||
|
(robotX,robotY,robotHeading,0.0, turretInterpolate);
|
||||||
|
|
||||||
desiredTurretAngle += manualOffset + error;
|
turret.trackGoal(deltaPose);
|
||||||
|
|
||||||
offset = desiredTurretAngle - 180 - (Math.toDegrees(robotHeading - headingOffset));
|
webcam.update();
|
||||||
|
|
||||||
if (offset > 135) {
|
|
||||||
offset -= 360;
|
|
||||||
}
|
|
||||||
|
|
||||||
double pos = turrDefault;
|
|
||||||
|
|
||||||
TELE.addData("offset", offset);
|
|
||||||
|
|
||||||
pos -= offset * ((double) 1 / 360);
|
|
||||||
|
|
||||||
if (pos < 0.13) {
|
|
||||||
pos = 0.13;
|
|
||||||
} else if (pos > 0.83) {
|
|
||||||
pos = 0.83;
|
|
||||||
}
|
|
||||||
|
|
||||||
//SHOOTER:
|
|
||||||
|
|
||||||
double powPID = flywheel.manageFlywheel((int) vel, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
|
||||||
|
|
||||||
robot.shooter1.setPower(powPID);
|
|
||||||
robot.shooter2.setPower(powPID);
|
|
||||||
|
|
||||||
//VELOCITY AUTOMATIC
|
//VELOCITY AUTOMATIC
|
||||||
|
if (targetingVel) {
|
||||||
if (autoVel) {
|
vel = targetingSettings.flywheelRPM;
|
||||||
|
} else if (autoVel) {
|
||||||
vel = velPrediction(distanceToGoal);
|
vel = velPrediction(distanceToGoal);
|
||||||
} else {
|
} else {
|
||||||
vel = manualVel;
|
vel = manualVel;
|
||||||
@@ -429,57 +426,39 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
manualVel = 3100;
|
manualVel = 3100;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
//SHOOTER:
|
||||||
|
flywheel.manageFlywheel(vel);
|
||||||
|
|
||||||
//TODO: test the camera teleop code
|
//TODO: test the camera teleop code
|
||||||
|
|
||||||
TELE.addData("posS2", pos);
|
// if (y < 0.3 && y > -0.3 && x < 0.3 && x > -0.3 && rx < 0.3 && rx > -0.3) { //not moving
|
||||||
|
// double bearing;
|
||||||
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) {
|
||||||
LLResult result = robot.limelight.getLatestResult();
|
// if (result.isValid()) {
|
||||||
if (result != null) {
|
// bearing = result.getTx() * bMult;
|
||||||
if (result.isValid()) {
|
//
|
||||||
bearing = result.getTx() * bMult;
|
// double bearingCorrection = bearing / bDiv;
|
||||||
|
//
|
||||||
double bearingCorrection = bearing / bDiv;
|
// error += bearingCorrection;
|
||||||
|
//
|
||||||
error += bearingCorrection;
|
// camTicker++;
|
||||||
|
// TELE.addData("tx", bearingCorrection);
|
||||||
camTicker++;
|
// TELE.addData("ty", result.getTy());
|
||||||
TELE.addData("tx", bearingCorrection);
|
// }
|
||||||
TELE.addData("ty", result.getTy());
|
// }
|
||||||
}
|
//
|
||||||
}
|
// } else {
|
||||||
|
// camTicker = 0;
|
||||||
} else {
|
// overrideTurr = false;
|
||||||
camTicker = 0;
|
// }
|
||||||
overrideTurr = false;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!overrideTurr) {
|
|
||||||
turretPos = pos;
|
|
||||||
}
|
|
||||||
|
|
||||||
TELE.addData("posS3", turretPos);
|
|
||||||
|
|
||||||
if (manualTurret) {
|
|
||||||
pos = turrDefault + (manualOffset / 100) + error;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!overrideTurr) {
|
|
||||||
turretPos = pos;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (Math.abs(gamepad2.left_stick_x)>0.2) {
|
|
||||||
manualOffset += 1.35 * gamepad2.left_stick_x;
|
|
||||||
}
|
|
||||||
|
|
||||||
robot.turr1.setPosition(pos);
|
|
||||||
robot.turr2.setPosition(1 - pos);
|
|
||||||
|
|
||||||
//HOOD:
|
//HOOD:
|
||||||
|
|
||||||
if (autoHood) {
|
if (targetingHood) {
|
||||||
|
robot.hood.setPosition(targetingSettings.hoodAngle);
|
||||||
|
} else if (autoHood) {
|
||||||
robot.hood.setPosition(0.15 + hoodOffset);
|
robot.hood.setPosition(0.15 + hoodOffset);
|
||||||
} else {
|
} else {
|
||||||
robot.hood.setPosition(hoodDefaultPos + hoodOffset);
|
robot.hood.setPosition(hoodDefaultPos + hoodOffset);
|
||||||
@@ -532,7 +511,7 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
// }
|
// }
|
||||||
// }
|
// }
|
||||||
|
|
||||||
if (gamepad1.left_bumper) {
|
if (gamepad1.left_bumper && !enableSpindexerManager) {
|
||||||
|
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
|
|
||||||
@@ -563,14 +542,14 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (gamepad1.leftBumperWasReleased()) {
|
if (gamepad1.leftBumperWasReleased() && !enableSpindexerManager) {
|
||||||
shootStamp = getRuntime();
|
shootStamp = getRuntime();
|
||||||
shootAll = true;
|
shootAll = true;
|
||||||
|
|
||||||
shooterTicker = 0;
|
shooterTicker = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (shootAll) {
|
if (shootAll && !enableSpindexerManager) {
|
||||||
|
|
||||||
TELE.addData("100% works", shootOrder);
|
TELE.addData("100% works", shootOrder);
|
||||||
|
|
||||||
@@ -602,6 +581,63 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (enableSpindexerManager) {
|
||||||
|
if (!shootAll) {
|
||||||
|
spindexer.processIntake();
|
||||||
|
}
|
||||||
|
|
||||||
|
// RIGHT_BUMPER
|
||||||
|
if (gamepad1.right_bumper) {
|
||||||
|
robot.intake.setPower(1);
|
||||||
|
|
||||||
|
} else {
|
||||||
|
robot.intake.setPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
// LEFT_BUMPER
|
||||||
|
if (!shootAll &&
|
||||||
|
(gamepad1.leftBumperWasReleased() ||
|
||||||
|
gamepad1.leftBumperWasPressed() ||
|
||||||
|
gamepad1.left_bumper)) {
|
||||||
|
shootStamp = getRuntime();
|
||||||
|
shootAll = true;
|
||||||
|
|
||||||
|
shooterTicker = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (shootAll) {
|
||||||
|
|
||||||
|
intake = false;
|
||||||
|
reject = false;
|
||||||
|
|
||||||
|
shooterTicker++;
|
||||||
|
|
||||||
|
// 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);
|
||||||
|
|
||||||
|
spindexer.resetSpindexer();
|
||||||
|
spindexer.processIntake();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
//
|
//
|
||||||
// if (shootAll) {
|
// if (shootAll) {
|
||||||
//
|
//
|
||||||
@@ -768,7 +804,6 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
// }
|
// }
|
||||||
|
|
||||||
//EXTRA STUFFINESS:
|
//EXTRA STUFFINESS:
|
||||||
|
|
||||||
drive.updatePoseEstimate();
|
drive.updatePoseEstimate();
|
||||||
|
|
||||||
for (LynxModule hub : allHubs) {
|
for (LynxModule hub : allHubs) {
|
||||||
@@ -784,13 +819,30 @@ public class TeleopV3 extends LinearOpMode {
|
|||||||
TELE.addData("distanceToGoal", distanceToGoal);
|
TELE.addData("distanceToGoal", distanceToGoal);
|
||||||
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(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()));
|
TELE.addData("Velocity", flywheel.getVelo());
|
||||||
|
|
||||||
TELE.addData("shootOrder", shootOrder);
|
TELE.addData("shootOrder", shootOrder);
|
||||||
TELE.addData("oddColor", oddBallColor);
|
TELE.addData("oddColor", oddBallColor);
|
||||||
|
|
||||||
|
// Spindexer Debug
|
||||||
TELE.addData("spinEqual", servo.spinEqual(spindexer_intakePos1));
|
TELE.addData("spinEqual", servo.spinEqual(spindexer_intakePos1));
|
||||||
|
TELE.addData("spinCommmandedPos", spindexer.commandedIntakePosition);
|
||||||
|
TELE.addData("spinIntakeState", spindexer.currentIntakeState);
|
||||||
|
TELE.addData("spinTestCounter", spindexer.counter);
|
||||||
TELE.addData("autoSpintake", autoSpintake);
|
TELE.addData("autoSpintake", autoSpintake);
|
||||||
|
//TELE.addData("distanceRearCenter", spindexer.distanceRearCenter);
|
||||||
|
//TELE.addData("distanceFrontDriver", spindexer.distanceFrontDriver);
|
||||||
|
//TELE.addData("distanceFrontPassenger", spindexer.distanceFrontPassenger);
|
||||||
|
TELE.addData("shootall commanded", shootAll);
|
||||||
|
// Targeting Debug
|
||||||
|
TELE.addData("robotX", robotX);
|
||||||
|
TELE.addData( "robotY", robotY);
|
||||||
|
TELE.addData("robotInchesX", targeting.robotInchesX);
|
||||||
|
TELE.addData( "robotInchesY", targeting.robotInchesY);
|
||||||
|
TELE.addData("Targeting Interpolate", turretInterpolate);
|
||||||
|
TELE.addData("Targeting GridX", targeting.robotGridX);
|
||||||
|
TELE.addData("Targeting GridY", targeting.robotGridY);
|
||||||
|
TELE.addData("Targeting FlyWheel", targetingSettings.flywheelRPM);
|
||||||
|
TELE.addData("Targeting HoodAngle", targetingSettings.hoodAngle);
|
||||||
TELE.addData("timeSinceStamp", getRuntime() - shootStamp);
|
TELE.addData("timeSinceStamp", getRuntime() - shootStamp);
|
||||||
|
|
||||||
TELE.update();
|
TELE.update();
|
||||||
|
|||||||
@@ -52,7 +52,6 @@ public class PIDServoTest extends LinearOpMode {
|
|||||||
}
|
}
|
||||||
|
|
||||||
telemetry.addData("pos", pos);
|
telemetry.addData("pos", pos);
|
||||||
telemetry.addData("Turret Voltage", robot.turr1Pos.getCurrentPosition());
|
|
||||||
telemetry.addData("Spindex Voltage", robot.spin1Pos.getVoltage());
|
telemetry.addData("Spindex Voltage", robot.spin1Pos.getVoltage());
|
||||||
telemetry.addData("target", target);
|
telemetry.addData("target", target);
|
||||||
telemetry.addData("Mode", mode);
|
telemetry.addData("Mode", mode);
|
||||||
|
|||||||
@@ -9,7 +9,7 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|||||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
|
|
||||||
import org.firstinspires.ftc.teamcode.utils.FlywheelV2;
|
import org.firstinspires.ftc.teamcode.utils.Flywheel;
|
||||||
import org.firstinspires.ftc.teamcode.utils.Robot;
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
|
||||||
@Config
|
@Config
|
||||||
@@ -21,12 +21,17 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
// --- 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 P = 40.0;
|
||||||
|
public static double I = 0.3;
|
||||||
|
public static double D = 7.0;
|
||||||
|
public static double F = 10.0;
|
||||||
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;
|
||||||
Robot robot;
|
Robot robot;
|
||||||
FlywheelV2 flywheel;
|
Flywheel flywheel;
|
||||||
|
|
||||||
@Override
|
@Override
|
||||||
public void runOpMode() throws InterruptedException {
|
public void runOpMode() throws InterruptedException {
|
||||||
@@ -34,7 +39,7 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
DcMotorEx leftShooter = robot.shooter1;
|
DcMotorEx leftShooter = robot.shooter1;
|
||||||
DcMotorEx rightShooter = robot.shooter2;
|
DcMotorEx rightShooter = robot.shooter2;
|
||||||
flywheel = new FlywheelV2();
|
flywheel = new Flywheel(hardwareMap);
|
||||||
|
|
||||||
MultipleTelemetry TELE = new MultipleTelemetry(
|
MultipleTelemetry TELE = new MultipleTelemetry(
|
||||||
telemetry, FtcDashboard.getInstance().getTelemetry()
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
@@ -50,10 +55,8 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
rightShooter.setPower(parameter);
|
rightShooter.setPower(parameter);
|
||||||
leftShooter.setPower(parameter);
|
leftShooter.setPower(parameter);
|
||||||
} else if (mode == 1) {
|
} else if (mode == 1) {
|
||||||
double powPID = flywheel.manageFlywheel((int) parameter, robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition());
|
flywheel.setPIDF(P,I,D,F);
|
||||||
rightShooter.setPower(powPID);
|
flywheel.manageFlywheel((int) Velocity);
|
||||||
leftShooter.setPower(powPID);
|
|
||||||
TELE.addData("PIDPower", powPID);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (hoodPos != 0.501) {
|
if (hoodPos != 0.501) {
|
||||||
@@ -67,7 +70,7 @@ public class ShooterTest extends LinearOpMode {
|
|||||||
} else {
|
} else {
|
||||||
robot.transferServo.setPosition(transferServo_out);
|
robot.transferServo.setPosition(transferServo_out);
|
||||||
}
|
}
|
||||||
TELE.addData("Velocity", flywheel.getVelo(robot.shooter1.getCurrentPosition(), robot.shooter2.getCurrentPosition()));
|
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());
|
||||||
TELE.addData("Power", robot.shooter1.getPower());
|
TELE.addData("Power", robot.shooter1.getPower());
|
||||||
|
|||||||
@@ -0,0 +1,50 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.tests;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.FtcDashboard;
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Robot;
|
||||||
|
import org.firstinspires.ftc.teamcode.utils.Turret;
|
||||||
|
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||||
|
|
||||||
|
@Autonomous
|
||||||
|
@Config
|
||||||
|
public class TurretTest extends LinearOpMode {
|
||||||
|
@Override
|
||||||
|
public void runOpMode() throws InterruptedException {
|
||||||
|
|
||||||
|
Robot robot = new Robot(hardwareMap);
|
||||||
|
MultipleTelemetry TELE = new MultipleTelemetry(
|
||||||
|
telemetry, FtcDashboard.getInstance().getTelemetry()
|
||||||
|
);
|
||||||
|
|
||||||
|
AprilTagWebcam webcam = new AprilTagWebcam();
|
||||||
|
webcam.init(robot, TELE);
|
||||||
|
|
||||||
|
Turret turret = new Turret(robot, TELE, webcam);
|
||||||
|
waitForStart();
|
||||||
|
|
||||||
|
|
||||||
|
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(15, 0,0));
|
||||||
|
|
||||||
|
while(opModeIsActive()){
|
||||||
|
|
||||||
|
drive.updatePoseEstimate();
|
||||||
|
turret.trackGoal(drive.localizer.getPose());
|
||||||
|
|
||||||
|
webcam.update();
|
||||||
|
webcam.displayAllTelemetry();
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
TELE.update();
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -1,88 +1,76 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.kP;
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
import static org.firstinspires.ftc.teamcode.constants.ShooterVars.maxStep;
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
|
||||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
|
||||||
|
|
||||||
public class Flywheel {
|
public class Flywheel {
|
||||||
Robot robot;
|
Robot robot;
|
||||||
MultipleTelemetry TELE;
|
public PIDFCoefficients shooterPIDF1, shooterPIDF2;
|
||||||
|
|
||||||
double initPos = 0.0;
|
|
||||||
double stamp = 0.0;
|
|
||||||
double stamp1 = 0.0;
|
|
||||||
double ticker = 0.0;
|
|
||||||
double currentPos = 0.0;
|
|
||||||
double velo = 0.0;
|
double velo = 0.0;
|
||||||
double velo1 = 0.0;
|
double velo1 = 0.0;
|
||||||
double velo2 = 0.0;
|
double velo2 = 0.0;
|
||||||
double velo3 = 0.0;
|
|
||||||
double velo4 = 0.0;
|
|
||||||
double velo5 = 0.0;
|
|
||||||
double targetVelocity = 0.0;
|
double targetVelocity = 0.0;
|
||||||
double powPID = 0.0;
|
double powPID = 0.0;
|
||||||
boolean steady = false;
|
boolean steady = false;
|
||||||
public Flywheel () {
|
public Flywheel (HardwareMap hardwareMap) {
|
||||||
//robot = new Robot(hardwareMap);
|
robot = new Robot(hardwareMap);
|
||||||
|
shooterPIDF1 = new PIDFCoefficients
|
||||||
|
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
|
||||||
|
shooterPIDF2 = new PIDFCoefficients
|
||||||
|
(robot.shooterPIDF_P, robot.shooterPIDF_I, robot.shooterPIDF_D, robot.shooterPIDF_F);
|
||||||
}
|
}
|
||||||
|
|
||||||
public double getVelo () {
|
public double getVelo () {
|
||||||
return velo;
|
return velo;
|
||||||
}
|
}
|
||||||
|
public double getVelo1 () {
|
||||||
|
return velo1;
|
||||||
|
}
|
||||||
|
public double getVelo2 () {
|
||||||
|
return velo2;
|
||||||
|
}
|
||||||
|
|
||||||
public boolean getSteady() {
|
public boolean getSteady() {
|
||||||
return steady;
|
return steady;
|
||||||
}
|
}
|
||||||
|
|
||||||
private double getTimeSeconds ()
|
// Set the robot PIDF for the next cycle.
|
||||||
{
|
public void setPIDF(double p, double i, double d, double f) {
|
||||||
return (double) System.currentTimeMillis()/1000.0;
|
robot.shooterPIDF.p = p;
|
||||||
|
robot.shooterPIDF.i = i;
|
||||||
|
robot.shooterPIDF.d = d;
|
||||||
|
robot.shooterPIDF.f = f;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// Convert from RPM to Ticks per Second
|
||||||
|
private double RPM_to_TPS (double RPM) { return (RPM*28.0)/60.0;}
|
||||||
|
|
||||||
public double manageFlywheel(int commandedVelocity, double shooter1CurPos) {
|
// Convert from Ticks per Second to RPM
|
||||||
|
private double TPS_to_RPM (double TPS) { return (TPS*60.0)/28.0;}
|
||||||
|
|
||||||
|
public double manageFlywheel(double commandedVelocity) {
|
||||||
targetVelocity = commandedVelocity;
|
targetVelocity = commandedVelocity;
|
||||||
|
|
||||||
ticker++;
|
// Add code here to set PIDF based on desired RPM
|
||||||
if (ticker % 2 == 0) {
|
//robot.shooterPIDF.p = P;
|
||||||
velo5 = velo4;
|
//robot.shooterPIDF.i = I;
|
||||||
velo4 = velo3;
|
//robot.shooterPIDF.d = D;
|
||||||
velo3 = velo2;
|
//robot.shooterPIDF.f = F;
|
||||||
velo2 = velo1;
|
|
||||||
|
|
||||||
currentPos = shooter1CurPos / 2048;
|
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF1);
|
||||||
stamp = getTimeSeconds(); //getRuntime();
|
robot.shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF2);
|
||||||
velo1 = -60 * ((currentPos - initPos) / (stamp - stamp1));
|
robot.shooter1.setVelocity(RPM_to_TPS(targetVelocity));
|
||||||
initPos = currentPos;
|
robot.shooter2.setVelocity(RPM_to_TPS(targetVelocity));
|
||||||
stamp1 = stamp;
|
|
||||||
|
|
||||||
velo = (velo1 + velo2 + velo3 + velo4 + velo5) / 5;
|
// Record Current Velocity
|
||||||
}
|
velo1 = TPS_to_RPM(robot.shooter1.getVelocity());
|
||||||
// Flywheel control code here
|
velo2 = TPS_to_RPM(robot.shooter2.getVelocity());
|
||||||
if (targetVelocity - velo > 500) {
|
velo = Math.max(velo1,velo2);
|
||||||
powPID = 1.0;
|
|
||||||
} else if (velo - targetVelocity > 500){
|
|
||||||
powPID = 0.0;
|
|
||||||
} else {
|
|
||||||
double feed = Math.log((668.39 / (targetVelocity + 591.96)) - 0.116) / -4.18;
|
|
||||||
|
|
||||||
// --- PROPORTIONAL CORRECTION ---
|
|
||||||
double error = targetVelocity - velo;
|
|
||||||
double correction = kP * error;
|
|
||||||
|
|
||||||
// limit how fast power changes (prevents oscillation)
|
|
||||||
correction = Math.max(-maxStep, Math.min(maxStep, correction));
|
|
||||||
|
|
||||||
// --- FINAL MOTOR POWER ---
|
|
||||||
powPID = feed + correction;
|
|
||||||
|
|
||||||
// clamp to allowed range
|
|
||||||
powPID = Math.max(0, Math.min(1, powPID));
|
|
||||||
}
|
|
||||||
|
|
||||||
// really should be a running average of the last 5
|
// really should be a running average of the last 5
|
||||||
steady = (Math.abs(targetVelocity - velo) < 100.0);
|
steady = (Math.abs(targetVelocity - velo) < 200.0);
|
||||||
|
|
||||||
return powPID;
|
return powPID;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -71,7 +71,6 @@ public class PositionalServoProgrammer extends LinearOpMode {
|
|||||||
TELE.addData("spindexer voltage 2", robot.spin2Pos.getVoltage());
|
TELE.addData("spindexer voltage 2", robot.spin2Pos.getVoltage());
|
||||||
TELE.addData("hood pos", robot.hood.getPosition());
|
TELE.addData("hood pos", robot.hood.getPosition());
|
||||||
TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage());
|
TELE.addData("transferServo voltage", robot.transferServoPos.getVoltage());
|
||||||
TELE.addData("turret voltage", robot.turr1Pos.getCurrentPosition());
|
|
||||||
TELE.addData("spindexer pow", robot.spin1.getPower());
|
TELE.addData("spindexer pow", robot.spin1.getPower());
|
||||||
TELE.update();
|
TELE.update();
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,5 +1,6 @@
|
|||||||
package org.firstinspires.ftc.teamcode.utils;
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
import com.qualcomm.hardware.limelightvision.Limelight3A;
|
||||||
import com.qualcomm.hardware.rev.RevColorSensorV3;
|
import com.qualcomm.hardware.rev.RevColorSensorV3;
|
||||||
import com.qualcomm.robotcore.hardware.AnalogInput;
|
import com.qualcomm.robotcore.hardware.AnalogInput;
|
||||||
@@ -8,21 +9,31 @@ import com.qualcomm.robotcore.hardware.DcMotor;
|
|||||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
|
||||||
import com.qualcomm.robotcore.hardware.Servo;
|
import com.qualcomm.robotcore.hardware.Servo;
|
||||||
|
|
||||||
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
|
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
|
||||||
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
|
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
|
||||||
|
|
||||||
|
@Config
|
||||||
public class Robot {
|
public class Robot {
|
||||||
|
|
||||||
//Initialize Public Components
|
//Initialize Public Components
|
||||||
|
|
||||||
|
public static boolean usingLimelight = false;
|
||||||
|
public static boolean usingCamera = true;
|
||||||
public DcMotorEx frontLeft;
|
public DcMotorEx frontLeft;
|
||||||
public DcMotorEx frontRight;
|
public DcMotorEx frontRight;
|
||||||
public DcMotorEx backLeft;
|
public DcMotorEx backLeft;
|
||||||
public DcMotorEx backRight;
|
public DcMotorEx backRight;
|
||||||
public DcMotorEx intake;
|
public DcMotorEx intake;
|
||||||
public DcMotorEx transfer;
|
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_StepSizes = {10.0, 1.0, 0.001, 0.0001};
|
||||||
public DcMotorEx shooter1;
|
public DcMotorEx shooter1;
|
||||||
public DcMotorEx shooter2;
|
public DcMotorEx shooter2;
|
||||||
public Servo hood;
|
public Servo hood;
|
||||||
@@ -33,7 +44,7 @@ public class Robot {
|
|||||||
public CRServo spin2;
|
public CRServo spin2;
|
||||||
public AnalogInput spin1Pos;
|
public AnalogInput spin1Pos;
|
||||||
public AnalogInput spin2Pos;
|
public AnalogInput spin2Pos;
|
||||||
public DcMotorEx turr1Pos;
|
public AnalogInput turr1Pos;
|
||||||
public AnalogInput transferServoPos;
|
public AnalogInput transferServoPos;
|
||||||
public AprilTagProcessor aprilTagProcessor;
|
public AprilTagProcessor aprilTagProcessor;
|
||||||
public WebcamName webcam;
|
public WebcamName webcam;
|
||||||
@@ -42,10 +53,6 @@ public class Robot {
|
|||||||
public RevColorSensorV3 color3;
|
public RevColorSensorV3 color3;
|
||||||
public Limelight3A limelight;
|
public Limelight3A limelight;
|
||||||
|
|
||||||
public static boolean usingLimelight = true;
|
|
||||||
|
|
||||||
public static boolean usingCamera = true;
|
|
||||||
|
|
||||||
public Robot(HardwareMap hardwareMap) {
|
public Robot(HardwareMap hardwareMap) {
|
||||||
|
|
||||||
//Define components w/ hardware map
|
//Define components w/ hardware map
|
||||||
@@ -69,8 +76,13 @@ public class Robot {
|
|||||||
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
|
shooter2 = hardwareMap.get(DcMotorEx.class, "shooter2");
|
||||||
//TODO: figure out which shooter motor is reversed using ShooterTest and change it in code @KeshavAnandCode
|
//TODO: figure out which shooter motor is reversed using ShooterTest and change it in code @KeshavAnandCode
|
||||||
shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
|
shooter1.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||||
shooter1.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
shooterPIDF = new PIDFCoefficients(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F);
|
||||||
shooter2.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
shooter1.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||||
|
shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
||||||
|
shooter1.setVelocity(1400);
|
||||||
|
shooter2.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||||
|
shooter2.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
||||||
|
shooter2.setVelocity(1400);
|
||||||
|
|
||||||
hood = hardwareMap.get(Servo.class, "hood");
|
hood = hardwareMap.get(Servo.class, "hood");
|
||||||
|
|
||||||
@@ -78,7 +90,7 @@ public class Robot {
|
|||||||
|
|
||||||
turr2 = hardwareMap.get(Servo.class, "t2");
|
turr2 = hardwareMap.get(Servo.class, "t2");
|
||||||
|
|
||||||
turr1Pos = intake; // Encoder of turret plugged in intake port
|
turr1Pos = hardwareMap.get(AnalogInput.class, "t1Pos"); // Encoder of turret plugged in intake port
|
||||||
|
|
||||||
//TODO: check spindexer configuration (both servo and analog input) - check comments in PositionalServoProgrammer
|
//TODO: check spindexer configuration (both servo and analog input) - check comments in PositionalServoProgrammer
|
||||||
spin1 = hardwareMap.get(CRServo.class, "spin1");
|
spin1 = hardwareMap.get(CRServo.class, "spin1");
|
||||||
@@ -107,9 +119,9 @@ public class Robot {
|
|||||||
|
|
||||||
color3 = hardwareMap.get(RevColorSensorV3.class, "c3");
|
color3 = hardwareMap.get(RevColorSensorV3.class, "c3");
|
||||||
|
|
||||||
if (usingLimelight){
|
if (usingLimelight) {
|
||||||
limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
limelight = hardwareMap.get(Limelight3A.class, "limelight");
|
||||||
} else if (usingCamera){
|
} else if (usingCamera) {
|
||||||
webcam = hardwareMap.get(WebcamName.class, "Webcam 1");
|
webcam = hardwareMap.get(WebcamName.class, "Webcam 1");
|
||||||
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
|
aprilTagProcessor = AprilTagProcessor.easyCreateWithDefaults();
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -44,17 +44,15 @@ public class Servos {
|
|||||||
}
|
}
|
||||||
|
|
||||||
public double getTurrPos() {
|
public double getTurrPos() {
|
||||||
return (double) ((double) robot.turr1Pos.getCurrentPosition() / 1024.0) * ((double) 44.0 / (double) 77.0);
|
return 1.0;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
public double setTurrPos(double pos) {
|
public double setTurrPos(double pos) {
|
||||||
turretPID.setPIDF(turrP, turrI, turrD, turrF);
|
return 1.0;
|
||||||
|
|
||||||
return spinPID.calculate(this.getTurrPos(), pos);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
public boolean turretEqual(double pos) {
|
public boolean turretEqual(double pos) {
|
||||||
return Math.abs(pos - this.getTurrPos()) < 0.01;
|
return true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -0,0 +1,426 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.arcrobotics.ftclib.controller.PIDFController;
|
||||||
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos2;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_intakePos3;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall1;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall2;
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.ServoPositions.spindexer_outtakeBall3;
|
||||||
|
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;
|
||||||
|
import static org.firstinspires.ftc.teamcode.utils.Servos.spinP;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||||
|
import org.firstinspires.ftc.teamcode.libs.RR.MecanumDrive;
|
||||||
|
|
||||||
|
public class Spindexer {
|
||||||
|
Robot robot;
|
||||||
|
Servos servos;
|
||||||
|
Flywheel flywheel;
|
||||||
|
MecanumDrive drive;
|
||||||
|
double lastKnownSpinPos = 0.0;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
PIDFController spinPID = new PIDFController(spinP, spinI, spinD, spinF);
|
||||||
|
|
||||||
|
double spinCurrentPos = 0.0;
|
||||||
|
|
||||||
|
public int commandedIntakePosition = 0;
|
||||||
|
|
||||||
|
public double distanceRearCenter = 0.0;
|
||||||
|
public double distanceFrontDriver = 0.0;
|
||||||
|
public double distanceFrontPassenger = 0.0;
|
||||||
|
|
||||||
|
// For Use
|
||||||
|
enum RotatedBallPositionNames {
|
||||||
|
REARCENTER,
|
||||||
|
FRONTDRIVER,
|
||||||
|
FRONTPASSENGER
|
||||||
|
}
|
||||||
|
// Array of commandedIntakePositions with contents
|
||||||
|
// {RearCenter, FrontDriver, FrontPassenger}
|
||||||
|
static final int[][] RotatedBallPositions = {{0,2,1}, {1,0,2}, {2,1,0}};
|
||||||
|
class spindexerBallRoatation {
|
||||||
|
int rearCenter = 0; // aka commanded Position
|
||||||
|
int frontDriver = 0;
|
||||||
|
int frontPassenger = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
enum IntakeState {
|
||||||
|
UNKNOWN_START,
|
||||||
|
UNKNOWN_MOVE,
|
||||||
|
UNKNOWN_DETECT,
|
||||||
|
INTAKE,
|
||||||
|
FINDNEXT,
|
||||||
|
MOVING,
|
||||||
|
FULL,
|
||||||
|
SHOOTNEXT,
|
||||||
|
SHOOTMOVING,
|
||||||
|
SHOOTWAIT,
|
||||||
|
};
|
||||||
|
|
||||||
|
public IntakeState currentIntakeState = IntakeState.UNKNOWN_START;
|
||||||
|
public int unknownColorDetect = 0;
|
||||||
|
enum BallColor {
|
||||||
|
UNKNOWN,
|
||||||
|
GREEN,
|
||||||
|
PURPLE
|
||||||
|
};
|
||||||
|
|
||||||
|
class BallPosition {
|
||||||
|
boolean isEmpty = true;
|
||||||
|
int foundEmpty = 0;
|
||||||
|
BallColor ballColor = BallColor.UNKNOWN;
|
||||||
|
}
|
||||||
|
|
||||||
|
BallPosition[] ballPositions = new BallPosition[3];
|
||||||
|
|
||||||
|
public boolean init () {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
public Spindexer(HardwareMap hardwareMap) {
|
||||||
|
robot = new Robot(hardwareMap);
|
||||||
|
servos = new Servos(hardwareMap);
|
||||||
|
flywheel = new Flywheel(hardwareMap);
|
||||||
|
//TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||||
|
|
||||||
|
lastKnownSpinPos = servos.getSpinPos();
|
||||||
|
|
||||||
|
ballPositions[0] = new BallPosition();
|
||||||
|
ballPositions[1] = new BallPosition();
|
||||||
|
ballPositions[2] = new BallPosition();
|
||||||
|
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
double[] outakePositions =
|
||||||
|
{spindexer_outtakeBall1, spindexer_outtakeBall2, spindexer_outtakeBall3};
|
||||||
|
|
||||||
|
double[] intakePositions =
|
||||||
|
{spindexer_intakePos1, spindexer_intakePos2, spindexer_intakePos3};
|
||||||
|
|
||||||
|
public int counter = 0;
|
||||||
|
|
||||||
|
// private double getTimeSeconds ()
|
||||||
|
// {
|
||||||
|
// return (double) System.currentTimeMillis()/1000.0;
|
||||||
|
// }
|
||||||
|
|
||||||
|
// public double getPos() {
|
||||||
|
// robot.spin1Pos.getVoltage();
|
||||||
|
// robot.spin1Pos.getMaxVoltage();
|
||||||
|
// return (robot.spin1Pos.getVoltage()/robot.spin1Pos.getMaxVoltage());
|
||||||
|
// }
|
||||||
|
|
||||||
|
// public void manageSpindexer() {
|
||||||
|
//
|
||||||
|
// }
|
||||||
|
|
||||||
|
public void resetBallPosition (int pos) {
|
||||||
|
ballPositions[pos].isEmpty = true;
|
||||||
|
ballPositions[pos].foundEmpty = 0;
|
||||||
|
ballPositions[pos].ballColor = BallColor.UNKNOWN;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void resetSpindexer () {
|
||||||
|
for (int i = 0; i < 3; i++) {
|
||||||
|
resetBallPosition(i);
|
||||||
|
}
|
||||||
|
currentIntakeState = IntakeState.UNKNOWN_START;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Detects if a ball is found and what color.
|
||||||
|
// Returns true is there was a new ball found in Position 1
|
||||||
|
// FIXIT: Reduce number of times that we read the color sensors for loop times.
|
||||||
|
public boolean detectBalls(boolean detectRearColor, boolean detectFrontColor) {
|
||||||
|
|
||||||
|
boolean newPos1Detection = false;
|
||||||
|
int spindexerBallPos = 0;
|
||||||
|
|
||||||
|
// Read Distances
|
||||||
|
distanceRearCenter = robot.color1.getDistance(DistanceUnit.MM);
|
||||||
|
distanceFrontDriver = robot.color2.getDistance(DistanceUnit.MM);
|
||||||
|
distanceFrontPassenger = robot.color3.getDistance(DistanceUnit.MM);
|
||||||
|
|
||||||
|
// Position 1
|
||||||
|
if (distanceRearCenter < 43) {
|
||||||
|
|
||||||
|
// Mark Ball Found
|
||||||
|
newPos1Detection = true;
|
||||||
|
|
||||||
|
if (detectRearColor) {
|
||||||
|
// Detect which color
|
||||||
|
double green = robot.color1.getNormalizedColors().green;
|
||||||
|
double red = robot.color1.getNormalizedColors().red;
|
||||||
|
double blue = robot.color1.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
// FIXIT - Add filtering to improve accuracy.
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
ballPositions[commandedIntakePosition].ballColor = BallColor.PURPLE; // purple
|
||||||
|
} else {
|
||||||
|
ballPositions[commandedIntakePosition].ballColor = BallColor.GREEN; // purple
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
// Position 2
|
||||||
|
// Find which ball position this is in the spindexer
|
||||||
|
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTDRIVER.ordinal()];
|
||||||
|
if (distanceFrontDriver < 60) {
|
||||||
|
// reset FoundEmpty because looking for 3 in a row before reset
|
||||||
|
ballPositions[spindexerBallPos].foundEmpty = 0;
|
||||||
|
if (detectFrontColor) {
|
||||||
|
double green = robot.color2.getNormalizedColors().green;
|
||||||
|
double red = robot.color2.getNormalizedColors().red;
|
||||||
|
double blue = robot.color2.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
ballPositions[spindexerBallPos].ballColor = BallColor.PURPLE; // purple
|
||||||
|
} else {
|
||||||
|
ballPositions[spindexerBallPos].ballColor = BallColor.GREEN; // purple
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
if (!ballPositions[spindexerBallPos].isEmpty) {
|
||||||
|
if (ballPositions[spindexerBallPos].foundEmpty > 3) {
|
||||||
|
resetBallPosition(spindexerBallPos);
|
||||||
|
}
|
||||||
|
ballPositions[spindexerBallPos].foundEmpty++;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
// Position 3
|
||||||
|
spindexerBallPos = RotatedBallPositions[commandedIntakePosition][RotatedBallPositionNames.FRONTPASSENGER.ordinal()];
|
||||||
|
if (distanceFrontPassenger < 33) {
|
||||||
|
|
||||||
|
// reset FoundEmpty because looking for 3 in a row before reset
|
||||||
|
ballPositions[spindexerBallPos].foundEmpty = 0;
|
||||||
|
if (detectFrontColor) {
|
||||||
|
double green = robot.color3.getNormalizedColors().green;
|
||||||
|
double red = robot.color3.getNormalizedColors().red;
|
||||||
|
double blue = robot.color3.getNormalizedColors().blue;
|
||||||
|
|
||||||
|
double gP = green / (green + red + blue);
|
||||||
|
|
||||||
|
if (gP >= 0.4) {
|
||||||
|
ballPositions[spindexerBallPos].ballColor = BallColor.PURPLE; // purple
|
||||||
|
} else {
|
||||||
|
ballPositions[spindexerBallPos].ballColor = BallColor.GREEN; // purple
|
||||||
|
}
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
if (!ballPositions[spindexerBallPos].isEmpty) {
|
||||||
|
if (ballPositions[spindexerBallPos].foundEmpty > 3) {
|
||||||
|
resetBallPosition(spindexerBallPos);
|
||||||
|
}
|
||||||
|
ballPositions[spindexerBallPos].foundEmpty++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// TELE.addData("Velocity", velo);
|
||||||
|
// TELE.addLine("Detecting");
|
||||||
|
// TELE.addData("Distance 1", s1D);
|
||||||
|
// TELE.addData("Distance 2", s2D);
|
||||||
|
// TELE.addData("Distance 3", s3D);
|
||||||
|
// TELE.addData("B1", b1);
|
||||||
|
// TELE.addData("B2", b2);
|
||||||
|
// TELE.addData("B3", b3);
|
||||||
|
// TELE.update();
|
||||||
|
|
||||||
|
return newPos1Detection;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void moveSpindexerToPos(double pos) {
|
||||||
|
spinCurrentPos = servos.getSpinPos();
|
||||||
|
|
||||||
|
double spindexPID = spinPID.calculate(spinCurrentPos, pos);
|
||||||
|
|
||||||
|
robot.spin1.setPower(spindexPID);
|
||||||
|
robot.spin2.setPower(-spindexPID);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void stopSpindexer() {
|
||||||
|
robot.spin1.setPower(0);
|
||||||
|
robot.spin2.setPower(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean isFull () {
|
||||||
|
return (!ballPositions[0].isEmpty && !ballPositions[1].isEmpty && !ballPositions[2].isEmpty);
|
||||||
|
}
|
||||||
|
public boolean processIntake() {
|
||||||
|
|
||||||
|
switch (currentIntakeState) {
|
||||||
|
case UNKNOWN_START:
|
||||||
|
// For now just set position ONE if UNKNOWN
|
||||||
|
commandedIntakePosition = 0;
|
||||||
|
servos.setSpinPos(intakePositions[0]);
|
||||||
|
currentIntakeState = Spindexer.IntakeState.UNKNOWN_MOVE;
|
||||||
|
break;
|
||||||
|
case UNKNOWN_MOVE:
|
||||||
|
// Stopping when we get to the new position
|
||||||
|
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||||
|
currentIntakeState = Spindexer.IntakeState.UNKNOWN_DETECT;
|
||||||
|
stopSpindexer();
|
||||||
|
detectBalls(true, true);
|
||||||
|
unknownColorDetect = 0;
|
||||||
|
} else {
|
||||||
|
// Keep moving the spindexer
|
||||||
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case UNKNOWN_DETECT:
|
||||||
|
if (unknownColorDetect >5) {
|
||||||
|
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||||
|
} else {
|
||||||
|
detectBalls(true, true);
|
||||||
|
unknownColorDetect++;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case INTAKE:
|
||||||
|
// Ready for intake and Detecting a New Ball
|
||||||
|
if (detectBalls(true, false)) {
|
||||||
|
ballPositions[commandedIntakePosition].isEmpty = false;
|
||||||
|
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||||
|
} else {
|
||||||
|
// Maintain Position
|
||||||
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case FINDNEXT:
|
||||||
|
// Find Next Open Position and start movement
|
||||||
|
double currentSpindexerPos = servos.getSpinPos();
|
||||||
|
double commandedtravelDistance = 2.0;
|
||||||
|
double proposedTravelDistance = Math.abs(intakePositions[0] - currentSpindexerPos);
|
||||||
|
if (ballPositions[0].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||||
|
// Position 1
|
||||||
|
commandedIntakePosition = 0;
|
||||||
|
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||||
|
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||||
|
commandedtravelDistance = proposedTravelDistance;
|
||||||
|
}
|
||||||
|
proposedTravelDistance = Math.abs(intakePositions[1] - currentSpindexerPos);
|
||||||
|
if (ballPositions[1].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||||
|
// Position 2
|
||||||
|
commandedIntakePosition = 1;
|
||||||
|
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||||
|
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||||
|
commandedtravelDistance = proposedTravelDistance;
|
||||||
|
}
|
||||||
|
proposedTravelDistance = Math.abs(intakePositions[2] - currentSpindexerPos);
|
||||||
|
if (ballPositions[2].isEmpty && (proposedTravelDistance < commandedtravelDistance)) {
|
||||||
|
// Position 3
|
||||||
|
commandedIntakePosition = 2;
|
||||||
|
servos.setSpinPos(intakePositions[commandedIntakePosition]);
|
||||||
|
currentIntakeState = Spindexer.IntakeState.MOVING;
|
||||||
|
commandedtravelDistance = proposedTravelDistance;
|
||||||
|
}
|
||||||
|
if (currentIntakeState != Spindexer.IntakeState.MOVING) {
|
||||||
|
// Full
|
||||||
|
currentIntakeState = Spindexer.IntakeState.FULL;
|
||||||
|
}
|
||||||
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case MOVING:
|
||||||
|
// Stopping when we get to the new position
|
||||||
|
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||||
|
currentIntakeState = Spindexer.IntakeState.INTAKE;
|
||||||
|
stopSpindexer();
|
||||||
|
detectBalls(false, false);
|
||||||
|
} else {
|
||||||
|
// Keep moving the spindexer
|
||||||
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case FULL:
|
||||||
|
// Double Check Colors
|
||||||
|
detectBalls(false, false); // Minimize hardware calls
|
||||||
|
if (ballPositions[0].isEmpty || ballPositions[1].isEmpty || ballPositions[2].isEmpty) {
|
||||||
|
// Error handling found an empty spot, get it ready for a ball
|
||||||
|
currentIntakeState = Spindexer.IntakeState.FINDNEXT;
|
||||||
|
}
|
||||||
|
// Maintain Position
|
||||||
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
|
break;
|
||||||
|
|
||||||
|
case SHOOTNEXT:
|
||||||
|
// Find Next Open Position and start movement
|
||||||
|
if (!ballPositions[0].isEmpty) {
|
||||||
|
// Position 1
|
||||||
|
commandedIntakePosition = 0;
|
||||||
|
servos.setSpinPos(outakePositions[commandedIntakePosition]);
|
||||||
|
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
||||||
|
} else if (ballPositions[1].isEmpty) { // Possible error: should it be !ballPosition[1].isEmpty?
|
||||||
|
// Position 2
|
||||||
|
commandedIntakePosition = 1;
|
||||||
|
servos.setSpinPos(outakePositions[commandedIntakePosition]);
|
||||||
|
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
||||||
|
} else if (ballPositions[2].isEmpty) { // Possible error: should it be !ballPosition[2].isEmpty?
|
||||||
|
// Position 3
|
||||||
|
commandedIntakePosition = 2;
|
||||||
|
servos.setSpinPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
||||||
|
currentIntakeState = Spindexer.IntakeState.SHOOTMOVING;
|
||||||
|
} else {
|
||||||
|
// Empty return to intake state
|
||||||
|
currentIntakeState = IntakeState.FINDNEXT;
|
||||||
|
}
|
||||||
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]); // Possible error: should it be using "outakePositions" instead of "intakePositions"
|
||||||
|
break;
|
||||||
|
|
||||||
|
case SHOOTMOVING:
|
||||||
|
// 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"
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
case SHOOTWAIT:
|
||||||
|
// Stopping when we get to the new position
|
||||||
|
if (servos.spinEqual(intakePositions[commandedIntakePosition])) {
|
||||||
|
currentIntakeState = Spindexer.IntakeState.INTAKE;
|
||||||
|
stopSpindexer();
|
||||||
|
detectBalls(true, false);
|
||||||
|
} else {
|
||||||
|
// Keep moving the spindexer
|
||||||
|
moveSpindexerToPos(intakePositions[commandedIntakePosition]);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
// Statements to execute if no case matches
|
||||||
|
}
|
||||||
|
//TELE.addData("commandedIntakePosition", commandedIntakePosition);
|
||||||
|
//TELE.update();
|
||||||
|
// Signal a successful intake
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
public void update()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,141 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import android.provider.Settings;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||||
|
|
||||||
|
public class Targeting {
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
|
||||||
|
double cancelOffsetX = 7.071067811;
|
||||||
|
double cancelOffsetY = 7.071067811;
|
||||||
|
double unitConversionFactor = 0.95;
|
||||||
|
|
||||||
|
int tileSize = 24; //inches
|
||||||
|
|
||||||
|
public double robotInchesX, robotInchesY = 0.0;
|
||||||
|
|
||||||
|
public int robotGridX, robotGridY = 0;
|
||||||
|
|
||||||
|
|
||||||
|
public static class Settings {
|
||||||
|
public double flywheelRPM = 0.0;
|
||||||
|
public double hoodAngle = 0.0;
|
||||||
|
|
||||||
|
public Settings (double flywheelRPM, double hoodAngle) {
|
||||||
|
this.flywheelRPM = flywheelRPM;
|
||||||
|
this.hoodAngle = hoodAngle;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Known settings discovered using shooter test.
|
||||||
|
// Keep the fidelity at 1 floor tile for now but we could also half it if more
|
||||||
|
// accuracy is needed.
|
||||||
|
public static final Settings[][] KNOWNTARGETING;
|
||||||
|
static {
|
||||||
|
KNOWNTARGETING = new Settings[6][6];
|
||||||
|
// ROW 0 - Closet to the goals
|
||||||
|
KNOWNTARGETING[0][0] = new Settings (3000.0, 0.25);
|
||||||
|
KNOWNTARGETING[0][1] = new Settings (3001.0, 0.25);
|
||||||
|
KNOWNTARGETING[0][2] = new Settings (3002.0, 0.25);
|
||||||
|
KNOWNTARGETING[0][3] = new Settings (3302.0, 0.2);
|
||||||
|
KNOWNTARGETING[0][4] = new Settings (3503.0, 0.15);
|
||||||
|
KNOWNTARGETING[0][5] = new Settings (3505.0, 0.15);
|
||||||
|
// ROW 1
|
||||||
|
KNOWNTARGETING[1][0] = new Settings (3010.0, 0.25);
|
||||||
|
KNOWNTARGETING[1][1] = new Settings (3011.0, 0.25);
|
||||||
|
KNOWNTARGETING[1][2] = new Settings (3012.0, 0.25);
|
||||||
|
KNOWNTARGETING[1][3] = new Settings (3313.0, 0.15);
|
||||||
|
KNOWNTARGETING[1][4] = new Settings (3514.0, 0.15);
|
||||||
|
KNOWNTARGETING[1][5] = new Settings (3515.0, 0.15);
|
||||||
|
// ROW 2
|
||||||
|
KNOWNTARGETING[2][0] = new Settings (3020.0, 0.1);
|
||||||
|
KNOWNTARGETING[2][1] = new Settings (3000.0, 0.25);
|
||||||
|
KNOWNTARGETING[2][2] = new Settings (3000.0, 0.15);
|
||||||
|
KNOWNTARGETING[2][3] = new Settings (3000.0, 0.15);
|
||||||
|
KNOWNTARGETING[2][4] = new Settings (3524.0, 0.15);
|
||||||
|
KNOWNTARGETING[2][5] = new Settings (3525.0, 0.15);
|
||||||
|
// ROW 3
|
||||||
|
KNOWNTARGETING[3][0] = new Settings (3030.0, 0.15);
|
||||||
|
KNOWNTARGETING[3][1] = new Settings (3031.0, 0.15);
|
||||||
|
KNOWNTARGETING[3][2] = new Settings (3000.0, 0.15);
|
||||||
|
KNOWNTARGETING[3][3] = new Settings (3000.0, 0.15);
|
||||||
|
KNOWNTARGETING[3][4] = new Settings (3000.0, 0.03);
|
||||||
|
KNOWNTARGETING[3][5] = new Settings (3535.0, 0.1);
|
||||||
|
// ROW 4
|
||||||
|
KNOWNTARGETING[4][0] = new Settings (4540.0, 0.1);
|
||||||
|
KNOWNTARGETING[4][1] = new Settings (4541.0, 0.1);
|
||||||
|
KNOWNTARGETING[4][2] = new Settings (4542.0, 0.1);
|
||||||
|
KNOWNTARGETING[4][3] = new Settings (4543.0, 0.1);
|
||||||
|
KNOWNTARGETING[4][4] = new Settings (4544.0, 0.1);
|
||||||
|
KNOWNTARGETING[4][5] = new Settings (4545.0, 0.1);
|
||||||
|
// ROW 1
|
||||||
|
KNOWNTARGETING[5][0] = new Settings (4550.0, 0.1);
|
||||||
|
KNOWNTARGETING[5][1] = new Settings (4551.0, 0.1);
|
||||||
|
KNOWNTARGETING[5][2] = new Settings (4552.0, 0.1);
|
||||||
|
KNOWNTARGETING[5][3] = new Settings (4553.0, 0.1);
|
||||||
|
KNOWNTARGETING[5][4] = new Settings (4554.0, 0.1);
|
||||||
|
KNOWNTARGETING[5][5] = new Settings (4555.0, 0.1);
|
||||||
|
}
|
||||||
|
|
||||||
|
public Targeting()
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
public Settings calculateSettings(double robotX, double robotY, double robotHeading, double robotVelocity, boolean interpolate) {
|
||||||
|
Settings recommendedSettings = new Settings(0.0, 0.0);
|
||||||
|
|
||||||
|
double cos45 = Math.cos(Math.toRadians(-45));
|
||||||
|
double sin45 = Math.sin(Math.toRadians(-45));
|
||||||
|
double rotatedY = (robotX - 40.0) * sin45 + (robotY + 7.0) * cos45;
|
||||||
|
double rotatedX = (robotX - 40.0) * cos45 - (robotY + 7.0) * sin45;
|
||||||
|
|
||||||
|
// Convert robot coordinates to inches
|
||||||
|
robotInchesX = rotatedX * unitConversionFactor;
|
||||||
|
robotInchesY = rotatedY * unitConversionFactor;
|
||||||
|
|
||||||
|
// Find approximate location in the grid
|
||||||
|
int gridX = Math.abs(Math.floorDiv((int) robotInchesX, tileSize) + 1);
|
||||||
|
int gridY = Math.abs(Math.floorDiv((int) robotInchesY, tileSize));
|
||||||
|
|
||||||
|
//clamp
|
||||||
|
robotGridX = Math.max(0, Math.min(gridX, KNOWNTARGETING[0].length - 1));
|
||||||
|
robotGridY = Math.max(0, Math.min(gridY, KNOWNTARGETING.length - 1));
|
||||||
|
|
||||||
|
// basic search
|
||||||
|
if(!interpolate) {
|
||||||
|
if ((robotGridY < 6) && (robotGridX <6)) {
|
||||||
|
recommendedSettings.flywheelRPM = KNOWNTARGETING[robotGridY][robotGridX].flywheelRPM;
|
||||||
|
recommendedSettings.hoodAngle = KNOWNTARGETING[robotGridY][robotGridX].hoodAngle;
|
||||||
|
}
|
||||||
|
return recommendedSettings;
|
||||||
|
} else {
|
||||||
|
|
||||||
|
// bilinear interpolation
|
||||||
|
int x0 = robotGridX;
|
||||||
|
int x1 = Math.min(x0 + 1, KNOWNTARGETING[0].length - 1);
|
||||||
|
int y0 = gridY;
|
||||||
|
int y1 = Math.min(y0 + 1, KNOWNTARGETING.length - 1);
|
||||||
|
|
||||||
|
double x = (robotInchesX - (x0 * tileSize)) / tileSize;
|
||||||
|
double y = (robotInchesY - (y0 * tileSize)) / tileSize;
|
||||||
|
|
||||||
|
double rpm00 = KNOWNTARGETING[y0][x0].flywheelRPM;
|
||||||
|
double rpm10 = KNOWNTARGETING[y0][x1].flywheelRPM;
|
||||||
|
double rpm01 = KNOWNTARGETING[y1][x0].flywheelRPM;
|
||||||
|
double rpm11 = KNOWNTARGETING[y1][x1].flywheelRPM;
|
||||||
|
|
||||||
|
double angle00 = KNOWNTARGETING[y0][x0].hoodAngle;
|
||||||
|
double angle10 = KNOWNTARGETING[y0][x1].hoodAngle;
|
||||||
|
double angle01 = KNOWNTARGETING[y1][x0].hoodAngle;
|
||||||
|
double angle11 = KNOWNTARGETING[y1][x1].hoodAngle;
|
||||||
|
|
||||||
|
recommendedSettings.flywheelRPM = (1 - x) * (1 - y) * rpm00 + x * (1 - y) * rpm10 + (1 - x) * y * rpm01 + x * y * rpm11;
|
||||||
|
recommendedSettings.hoodAngle = (1 - x) * (1 - y) * angle00 + x * (1 - y) * angle10 + (1 - x) * y * angle01 + x * y * angle11;
|
||||||
|
|
||||||
|
return recommendedSettings;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
@@ -0,0 +1,147 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.utils;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.constants.Color.redAlliance;
|
||||||
|
|
||||||
|
import com.acmerobotics.dashboard.config.Config;
|
||||||
|
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||||
|
import com.acmerobotics.roadrunner.Pose2d;
|
||||||
|
|
||||||
|
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
|
||||||
|
|
||||||
|
@Config
|
||||||
|
public class Turret {
|
||||||
|
|
||||||
|
public static double turretTolerance = 0.02;
|
||||||
|
public static double turrPosScalar = 1.009;
|
||||||
|
public static double turret180Range = 0.4;
|
||||||
|
public static double turrDefault = 0.4;
|
||||||
|
public static double cameraBearingEqual = 1;
|
||||||
|
public static double errorLearningRate = 0.15;
|
||||||
|
public static double turrMin = 0.2;
|
||||||
|
public static double turrMax = 0.8;
|
||||||
|
public static double deltaAngleThreshold = 0.02;
|
||||||
|
public static double angleMultiplier = 0.0;
|
||||||
|
Robot robot;
|
||||||
|
MultipleTelemetry TELE;
|
||||||
|
AprilTagWebcam webcam;
|
||||||
|
private int obeliskID = 0;
|
||||||
|
private double turrPos = 0.0;
|
||||||
|
private double offset = 0.0;
|
||||||
|
private double bearing = 0.0;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
public Turret(Robot rob, MultipleTelemetry tele, AprilTagWebcam cam) {
|
||||||
|
this.TELE = tele;
|
||||||
|
this.robot = rob;
|
||||||
|
this.webcam = cam;
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getTurrPos() {
|
||||||
|
return turrPosScalar * (robot.turr1Pos.getVoltage() / 3.3);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void manualSetTurret(double pos){
|
||||||
|
robot.turr1.setPosition(pos);
|
||||||
|
robot.turr2.setPosition(1-pos);
|
||||||
|
}
|
||||||
|
|
||||||
|
public boolean turretEqual(double pos) {
|
||||||
|
return Math.abs(pos - this.getTurrPos()) < turretTolerance;
|
||||||
|
}
|
||||||
|
|
||||||
|
public double getBearing() {
|
||||||
|
if (redAlliance) {
|
||||||
|
AprilTagDetection d24 = webcam.getTagById(24);
|
||||||
|
if (d24 != null) {
|
||||||
|
bearing = d24.ftcPose.bearing;
|
||||||
|
return bearing;
|
||||||
|
} else {
|
||||||
|
return 1000.0;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
AprilTagDetection d20 = webcam.getTagById(20);
|
||||||
|
if (d20 != null) {
|
||||||
|
bearing = d20.ftcPose.bearing;
|
||||||
|
return bearing;
|
||||||
|
} else {
|
||||||
|
return 1000.0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public int detectObelisk() {
|
||||||
|
AprilTagDetection id21 = webcam.getTagById(21);
|
||||||
|
AprilTagDetection id22 = webcam.getTagById(22);
|
||||||
|
AprilTagDetection id23 = webcam.getTagById(23);
|
||||||
|
if (id21 != null) {
|
||||||
|
obeliskID = 21;
|
||||||
|
} else if (id22 != null) {
|
||||||
|
obeliskID = 22;
|
||||||
|
} else if (id23 != null) {
|
||||||
|
obeliskID = 23;
|
||||||
|
}
|
||||||
|
return obeliskID;
|
||||||
|
}
|
||||||
|
|
||||||
|
public int getObeliskID() {
|
||||||
|
return obeliskID;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
/*
|
||||||
|
Param @deltaPos = Pose2d when subtracting robot x, y, heading from goal x, y, heading
|
||||||
|
*/
|
||||||
|
public void trackGoal(Pose2d deltaPos) {
|
||||||
|
|
||||||
|
/* ---------------- FIELD → TURRET GEOMETRY ---------------- */
|
||||||
|
|
||||||
|
// Angle from robot to goal in robot frame
|
||||||
|
double desiredTurretAngleDeg = Math.toDegrees(
|
||||||
|
Math.atan2(deltaPos.position.y, deltaPos.position.x)
|
||||||
|
);
|
||||||
|
|
||||||
|
// Robot heading (field → robot)
|
||||||
|
double robotHeadingDeg = Math.toDegrees(deltaPos.heading.toDouble());
|
||||||
|
|
||||||
|
// Turret angle needed relative to robot
|
||||||
|
double turretAngleDeg = desiredTurretAngleDeg - robotHeadingDeg;
|
||||||
|
|
||||||
|
turretAngleDeg = -turretAngleDeg;
|
||||||
|
|
||||||
|
// Normalize to [-180, 180]
|
||||||
|
while (turretAngleDeg > 180) turretAngleDeg -= 360;
|
||||||
|
while (turretAngleDeg < -180) turretAngleDeg += 360;
|
||||||
|
|
||||||
|
|
||||||
|
/* ---------------- APRILTAG CORRECTION ---------------- */
|
||||||
|
//
|
||||||
|
double tagBearingDeg = getBearing(); // + = target is to the left
|
||||||
|
|
||||||
|
if (tagBearingDeg != 1000.0 && Math.abs(tagBearingDeg) > cameraBearingEqual) {
|
||||||
|
// Slowly learn turret offset (persistent calibration)
|
||||||
|
offset -= tagBearingDeg * errorLearningRate;
|
||||||
|
}
|
||||||
|
|
||||||
|
turretAngleDeg += offset;
|
||||||
|
|
||||||
|
/* ---------------- ANGLE → SERVO ---------------- */
|
||||||
|
|
||||||
|
double turretPos = turrDefault + (turretAngleDeg * (turret180Range * 2.0) / 360);
|
||||||
|
|
||||||
|
// Clamp to servo range
|
||||||
|
turretPos = Math.max(turrMin, Math.min(turretPos, turrMax));
|
||||||
|
|
||||||
|
robot.turr1.setPosition(turretPos);
|
||||||
|
robot.turr2.setPosition(1.0 - turretPos);
|
||||||
|
|
||||||
|
/* ---------------- TELEMETRY ---------------- */
|
||||||
|
|
||||||
|
TELE.addData("Turret Angle", turretAngleDeg);
|
||||||
|
TELE.addData("Bearing", tagBearingDeg);
|
||||||
|
TELE.addData("Offset", offset);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
Reference in New Issue
Block a user