Compare commits
13 Commits
209c34b3fd
...
add-sorted
| Author | SHA1 | Date | |
|---|---|---|---|
| 9b92a59a75 | |||
| cca86f3691 | |||
| 8c2a655c5c | |||
| 9a4aca90ba | |||
| a3479d8816 | |||
| e9b9ffc3b8 | |||
| e7056812b4 | |||
| c15b9d58d4 | |||
| deefa19be4 | |||
| 3ae976c16d | |||
| 05f59d1820 | |||
| 128826f4fd | |||
| a89535830b |
@@ -27,16 +27,22 @@ public class TeleopV4 extends LinearOpMode {
|
||||
SpindexerTransferIntake spindexerTransferIntake;
|
||||
Turret turret;
|
||||
Flywheel flywheel;
|
||||
VelocityCommander commander;
|
||||
|
||||
ParkTilter parkTilter;
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
Robot.resetInstance();
|
||||
|
||||
robot = Robot.getInstance(hardwareMap);
|
||||
|
||||
TELE = new MultipleTelemetry(
|
||||
FtcDashboard.getInstance().getTelemetry(), telemetry
|
||||
);
|
||||
|
||||
commander = new VelocityCommander();
|
||||
drivetrain = new Drivetrain(robot, TELE);
|
||||
follower = Constants.createFollower(hardwareMap);
|
||||
Pose start = new Pose(teleStartPoseX, teleStartPoseY, Math.toRadians(teleStartPoseH));
|
||||
@@ -45,10 +51,12 @@ public class TeleopV4 extends LinearOpMode {
|
||||
flywheel = new Flywheel(robot);
|
||||
turret = new Turret(robot);
|
||||
|
||||
parkTilter = new ParkTilter(robot);
|
||||
|
||||
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel);
|
||||
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
|
||||
shooter.setState(Shooter.ShooterState.TRACK_GOAL);
|
||||
spindexerTransferIntake = new SpindexerTransferIntake(robot, TELE);
|
||||
shooter.setRedAlliance(Color.redAlliance);
|
||||
spindexerTransferIntake = new SpindexerTransferIntake(robot, TELE, commander);
|
||||
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
|
||||
|
||||
|
||||
@@ -57,21 +65,22 @@ public class TeleopV4 extends LinearOpMode {
|
||||
if (isStopRequested()) return;
|
||||
|
||||
while (opModeIsActive()) {
|
||||
|
||||
//Drivetrain
|
||||
|
||||
drivetrain.drive(
|
||||
-gamepad1.right_stick_y,
|
||||
gamepad1.right_stick_x,
|
||||
gamepad1.left_stick_x
|
||||
);
|
||||
|
||||
shooter.update();
|
||||
follower.update();
|
||||
|
||||
|
||||
shooter.update(robot.voltage.getVoltage());
|
||||
spindexerTransferIntake.update();
|
||||
|
||||
SpindexerTransferIntake.RapidMode state = spindexerTransferIntake.getRapidState();
|
||||
|
||||
if (gamepad1.xWasPressed() &&
|
||||
if (gamepad1.leftBumperWasPressed() &&
|
||||
(state == SpindexerTransferIntake.RapidMode.INTAKE ||
|
||||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF ||
|
||||
state == SpindexerTransferIntake.RapidMode.BEFORE_PULSE_OUT ||
|
||||
@@ -82,7 +91,7 @@ public class TeleopV4 extends LinearOpMode {
|
||||
spindexerTransferIntake.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
|
||||
}
|
||||
|
||||
if (gamepad1.aWasPressed() &&
|
||||
if (gamepad1.right_trigger > 0.5 &&
|
||||
(state == SpindexerTransferIntake.RapidMode.INTAKE ||
|
||||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF)) {
|
||||
|
||||
@@ -90,8 +99,7 @@ public class TeleopV4 extends LinearOpMode {
|
||||
SpindexerTransferIntake.RapidMode.HOLD_BALLS
|
||||
);
|
||||
}
|
||||
|
||||
if (gamepad1.yWasPressed()
|
||||
if (gamepad1.rightBumperWasPressed()
|
||||
&& state == SpindexerTransferIntake.RapidMode.HOLD_BALLS) {
|
||||
|
||||
spindexerTransferIntake.setRapidMode(
|
||||
@@ -99,6 +107,17 @@ public class TeleopV4 extends LinearOpMode {
|
||||
);
|
||||
}
|
||||
|
||||
if (gamepad1.dpad_down){
|
||||
parkTilter.park();
|
||||
} else if (gamepad1.dpad_up) {
|
||||
parkTilter.unpark();
|
||||
}
|
||||
|
||||
TELE.addData("Distance From Goal", commander.getDistance());
|
||||
TELE.addData("Hood Position", commander.getHoodPredicted());
|
||||
TELE.addData("Transfer Power", robot.transfer.getPower());
|
||||
TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM());
|
||||
TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity());
|
||||
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
@@ -130,7 +130,7 @@ public class Hardware_Tester extends LinearOpMode {
|
||||
// TELE.addData("Beam Break 3?", robot.beam3.isPressed());
|
||||
|
||||
NormalizedRGBA revColor = robot.revSensor.getNormalizedColors();
|
||||
TELE.addData("REV Distance", robot.revSensor.getDistance(DistanceUnit.MM));
|
||||
TELE.addData("REV Distance", robot.revSensor.getDistance(DistanceUnit.CM));
|
||||
TELE.addData("REV Green", revColor.green / (revColor.red + revColor.blue + revColor.green));
|
||||
|
||||
TELE.addData("Voltage Sensor", robot.voltage.getVoltage());
|
||||
|
||||
@@ -1,47 +1,39 @@
|
||||
package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseH;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseX;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseY;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.pedropathing.follower.Follower;
|
||||
import com.pedropathing.geometry.Pose;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
|
||||
import org.firstinspires.ftc.teamcode.constants.Color;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
|
||||
import org.firstinspires.ftc.teamcode.utilsv2.Flywheel;
|
||||
import org.firstinspires.ftc.teamcode.utilsv2.Robot;
|
||||
import org.firstinspires.ftc.teamcode.utilsv2.Shooter;
|
||||
import org.firstinspires.ftc.teamcode.utilsv2.Turret;
|
||||
import org.firstinspires.ftc.teamcode.utilsv2.*;
|
||||
|
||||
@Config
|
||||
@TeleOp
|
||||
@Config
|
||||
public class NewShooterTest extends LinearOpMode {
|
||||
|
||||
Robot robot;
|
||||
Flywheel flywheel;
|
||||
Turret turret;
|
||||
Drivetrain drivetrain;
|
||||
Shooter shooter;
|
||||
MultipleTelemetry TELE;
|
||||
Follower follower;
|
||||
SpindexerTransferIntake spindexerTransferIntake;
|
||||
Turret turret;
|
||||
Flywheel flywheel;
|
||||
VelocityCommander commander;
|
||||
ParkTilter parkTilter;
|
||||
|
||||
|
||||
public static boolean intake = true;
|
||||
public static boolean shoot = false;
|
||||
public static double intakePower = 1.0;
|
||||
public static double transferShootPower = -1;
|
||||
public static double transferIntakePower = -1;
|
||||
public static double turretPos = 0.51;
|
||||
public static double hoodPos = 0.51;
|
||||
public static double flywheel_velo = 0;
|
||||
|
||||
public static double shooterP = 255, shooterI = 0, shooterD = 0, shooterF = 75;
|
||||
|
||||
private enum ShootState {
|
||||
IDLE,
|
||||
WAIT_GATE,
|
||||
WAIT_PUSH
|
||||
}
|
||||
|
||||
private ShootState shootState = ShootState.IDLE;
|
||||
private long timestamp = 0;
|
||||
public static int flywheelVelo = 0;
|
||||
public static double hoodPos = 0.5;
|
||||
public static double transferPower = -0.7;
|
||||
// public static double turretPos = 0.51;
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
@@ -50,98 +42,90 @@ public class NewShooterTest extends LinearOpMode {
|
||||
|
||||
robot = Robot.getInstance(hardwareMap);
|
||||
|
||||
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||
TELE = new MultipleTelemetry(
|
||||
FtcDashboard.getInstance().getTelemetry(), telemetry
|
||||
);
|
||||
|
||||
commander = new VelocityCommander();
|
||||
drivetrain = new Drivetrain(robot, TELE);
|
||||
follower = Constants.createFollower(hardwareMap);
|
||||
Pose start = new Pose(teleStartPoseX, teleStartPoseY, Math.toRadians(teleStartPoseH));
|
||||
follower.setStartingPose(start);
|
||||
|
||||
flywheel = new Flywheel(robot);
|
||||
turret = new Turret(robot);
|
||||
|
||||
Shooter shooter = new Shooter(
|
||||
robot,
|
||||
TELE,
|
||||
Constants.createFollower(hardwareMap),
|
||||
true,
|
||||
turret,
|
||||
flywheel
|
||||
);
|
||||
parkTilter = new ParkTilter(robot);
|
||||
|
||||
shooter.setState(Shooter.ShooterState.MANUAL);
|
||||
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
|
||||
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
|
||||
shooter.setRedAlliance(Color.redAlliance);
|
||||
spindexerTransferIntake = new SpindexerTransferIntake(robot, TELE, commander);
|
||||
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
|
||||
|
||||
waitForStart();
|
||||
|
||||
if (isStopRequested()) return;
|
||||
|
||||
while (opModeIsActive()) {
|
||||
//Drivetrain
|
||||
drivetrain.drive(
|
||||
-gamepad1.right_stick_y,
|
||||
gamepad1.right_stick_x,
|
||||
gamepad1.left_stick_x
|
||||
);
|
||||
|
||||
follower.update();
|
||||
|
||||
shooter.setFlywheelVelocity(flywheelVelo);
|
||||
robot.setHoodPos(hoodPos);
|
||||
shooter.setTurretPosition(turretPos);
|
||||
shooter.setFlywheelVelocity(flywheel_velo);
|
||||
double voltage = robot.voltage.getVoltage();
|
||||
flywheel.setPIDF(shooterP, shooterI, shooterD, shooterF / voltage);
|
||||
// shooter.setTurretPosition(turretPos);
|
||||
shooter.update(robot.voltage.getVoltage());
|
||||
spindexerTransferIntake.update();
|
||||
|
||||
robot.setSpinPos(ServoPositions.spindexer_A2);
|
||||
SpindexerTransferIntake.RapidMode state = spindexerTransferIntake.getRapidState();
|
||||
|
||||
if (intake && !shoot) {
|
||||
if (gamepad1.leftBumperWasPressed() &&
|
||||
(state == SpindexerTransferIntake.RapidMode.INTAKE ||
|
||||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF ||
|
||||
state == SpindexerTransferIntake.RapidMode.BEFORE_PULSE_OUT ||
|
||||
state == SpindexerTransferIntake.RapidMode.PULSE_OUT ||
|
||||
state == SpindexerTransferIntake.RapidMode.PULSE_IN ||
|
||||
state == SpindexerTransferIntake.RapidMode.HOLD_BALLS)) {
|
||||
|
||||
shootState = ShootState.IDLE;
|
||||
|
||||
robot.setRapidFireBlockerPos(
|
||||
ServoPositions.rapidFireBlocker_Closed);
|
||||
|
||||
robot.setTransferPower(transferIntakePower);
|
||||
robot.setIntakePower(intakePower);
|
||||
robot.setTransferServoPos(
|
||||
ServoPositions.transferServo_out);
|
||||
} else if (shoot) {
|
||||
robot.setIntakePower(intakePower);
|
||||
|
||||
|
||||
switch (shootState) {
|
||||
|
||||
case IDLE:
|
||||
|
||||
robot.setTransferPower(transferShootPower);
|
||||
|
||||
timestamp = System.currentTimeMillis();
|
||||
shootState = ShootState.WAIT_GATE;
|
||||
|
||||
break;
|
||||
|
||||
case WAIT_GATE:
|
||||
|
||||
if (System.currentTimeMillis() - timestamp >= 300) {
|
||||
|
||||
robot.setRapidFireBlockerPos(
|
||||
ServoPositions.rapidFireBlocker_Open);
|
||||
|
||||
timestamp = System.currentTimeMillis();
|
||||
shootState = ShootState.WAIT_PUSH;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case WAIT_PUSH:
|
||||
|
||||
if (System.currentTimeMillis() - timestamp >= 100) {
|
||||
|
||||
robot.setTransferServoPos(
|
||||
ServoPositions.transferServo_in);
|
||||
|
||||
shootState = ShootState.IDLE;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
spindexerTransferIntake.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
|
||||
}
|
||||
|
||||
TELE.addData("Flywheel Velocity1", (robot.shooter1.getVelocity() * 60) / 28);
|
||||
TELE.addData("Flywheel Velocity2", (robot.shooter2.getVelocity() * 60) / 28);
|
||||
TELE.addData("Flywheel Averag Velocity", flywheel.getAverageVelocity());
|
||||
TELE.addData("PIDF Coefficients", Flywheel.shooterPIDF);
|
||||
TELE.addData("Power", flywheel.getShooterPower());
|
||||
TELE.update();
|
||||
if (gamepad1.right_trigger > 0.5 &&
|
||||
(state == SpindexerTransferIntake.RapidMode.INTAKE ||
|
||||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF)) {
|
||||
|
||||
shooter.update();
|
||||
spindexerTransferIntake.setRapidMode(
|
||||
SpindexerTransferIntake.RapidMode.HOLD_BALLS
|
||||
);
|
||||
}
|
||||
if (gamepad1.rightBumperWasPressed()
|
||||
&& state == SpindexerTransferIntake.RapidMode.HOLD_BALLS) {
|
||||
|
||||
spindexerTransferIntake.setRapidMode(
|
||||
SpindexerTransferIntake.RapidMode.INTAKE
|
||||
);
|
||||
}
|
||||
|
||||
if (gamepad1.dpad_down){
|
||||
parkTilter.park();
|
||||
} else if (gamepad1.dpad_up) {
|
||||
parkTilter.unpark();
|
||||
}
|
||||
|
||||
TELE.addData("Distance From Goal", commander.getDistance());
|
||||
TELE.addData("Hood Position", commander.getHoodPredicted());
|
||||
TELE.addData("Transfer Power", commander.getTransferPow());
|
||||
TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM());
|
||||
TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity());
|
||||
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -0,0 +1,141 @@
|
||||
package org.firstinspires.ftc.teamcode.tests;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseH;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseX;
|
||||
import static org.firstinspires.ftc.teamcode.constants.Front_Poses.teleStartPoseY;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.pedropathing.follower.Follower;
|
||||
import com.pedropathing.geometry.Pose;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.constants.Color;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
|
||||
import org.firstinspires.ftc.teamcode.utilsv2.*;
|
||||
|
||||
@TeleOp
|
||||
@Config
|
||||
public class SortedSpindexerTest extends LinearOpMode {
|
||||
Robot robot;
|
||||
Drivetrain drivetrain;
|
||||
Shooter shooter;
|
||||
MultipleTelemetry TELE;
|
||||
Follower follower;
|
||||
SpindexerTransferIntake spindexerTransferIntake;
|
||||
Turret turret;
|
||||
Flywheel flywheel;
|
||||
VelocityCommander commander;
|
||||
|
||||
ParkTilter parkTilter;
|
||||
public static String order = "GPP";
|
||||
|
||||
@Override
|
||||
public void runOpMode() throws InterruptedException {
|
||||
|
||||
Robot.resetInstance();
|
||||
|
||||
robot = Robot.getInstance(hardwareMap);
|
||||
|
||||
TELE = new MultipleTelemetry(
|
||||
FtcDashboard.getInstance().getTelemetry(), telemetry
|
||||
);
|
||||
|
||||
commander = new VelocityCommander();
|
||||
drivetrain = new Drivetrain(robot, TELE);
|
||||
follower = Constants.createFollower(hardwareMap);
|
||||
Pose start = new Pose(teleStartPoseX, teleStartPoseY, Math.toRadians(teleStartPoseH));
|
||||
follower.setStartingPose(start);
|
||||
|
||||
flywheel = new Flywheel(robot);
|
||||
turret = new Turret(robot);
|
||||
|
||||
parkTilter = new ParkTilter(robot);
|
||||
|
||||
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
|
||||
shooter.setState(Shooter.ShooterState.TRACK_GOAL);
|
||||
shooter.setRedAlliance(Color.redAlliance);
|
||||
spindexerTransferIntake = new SpindexerTransferIntake(robot, TELE, commander);
|
||||
spindexerTransferIntake.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.SORTED);
|
||||
|
||||
|
||||
waitForStart();
|
||||
|
||||
if (isStopRequested()) return;
|
||||
|
||||
while (opModeIsActive()) {
|
||||
|
||||
switch(order) {
|
||||
case "PPG":
|
||||
spindexerTransferIntake.setDesiredPattern(
|
||||
SpindexerTransferIntake.DesiredPattern.PPG
|
||||
);
|
||||
break;
|
||||
|
||||
case "PGP":
|
||||
spindexerTransferIntake.setDesiredPattern(
|
||||
SpindexerTransferIntake.DesiredPattern.PGP
|
||||
);
|
||||
break;
|
||||
|
||||
default:
|
||||
spindexerTransferIntake.setDesiredPattern(
|
||||
SpindexerTransferIntake.DesiredPattern.GPP
|
||||
);
|
||||
}
|
||||
|
||||
|
||||
//Drivetrain
|
||||
drivetrain.drive(
|
||||
-gamepad1.right_stick_y,
|
||||
gamepad1.right_stick_x,
|
||||
gamepad1.left_stick_x
|
||||
);
|
||||
|
||||
follower.update();
|
||||
|
||||
|
||||
shooter.update(robot.voltage.getVoltage());
|
||||
spindexerTransferIntake.update();
|
||||
|
||||
SpindexerTransferIntake.RapidMode state = spindexerTransferIntake.getRapidState();
|
||||
|
||||
if(gamepad1.leftBumperWasPressed()) {
|
||||
spindexerTransferIntake.startSortedShoot();
|
||||
}
|
||||
|
||||
if (gamepad1.right_trigger > 0.5 &&
|
||||
(state == SpindexerTransferIntake.RapidMode.INTAKE ||
|
||||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF)) {
|
||||
|
||||
spindexerTransferIntake.setRapidMode(
|
||||
SpindexerTransferIntake.RapidMode.HOLD_BALLS
|
||||
);
|
||||
}
|
||||
if (gamepad1.rightBumperWasPressed()
|
||||
&& state == SpindexerTransferIntake.RapidMode.HOLD_BALLS) {
|
||||
|
||||
spindexerTransferIntake.setRapidMode(
|
||||
SpindexerTransferIntake.RapidMode.INTAKE
|
||||
);
|
||||
}
|
||||
|
||||
if (gamepad1.dpad_down){
|
||||
parkTilter.park();
|
||||
} else if (gamepad1.dpad_up) {
|
||||
parkTilter.unpark();
|
||||
}
|
||||
|
||||
TELE.addData("Distance From Goal", commander.getDistance());
|
||||
TELE.addData("Hood Position", commander.getHoodPredicted());
|
||||
TELE.addData("Transfer Power", robot.transfer.getPower());
|
||||
TELE.addData("Theoretical Velocity RPM", commander.getPredictedRPM());
|
||||
TELE.addData("Actual Velocity RPM", flywheel.getAverageVelocity());
|
||||
|
||||
TELE.update();
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
@@ -1,5 +1,6 @@
|
||||
package org.firstinspires.ftc.teamcode.utilsv2;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
@@ -9,15 +10,16 @@ import org.firstinspires.ftc.teamcode.utilsv2.Robot;
|
||||
|
||||
import java.util.LinkedList;
|
||||
|
||||
@Config
|
||||
public class Flywheel {
|
||||
Robot robot;
|
||||
|
||||
// public PIDFCoefficients shooterPIDF1, shooterPIDF2;
|
||||
public static PIDFCoefficients shooterPIDF;
|
||||
public static double shooterPIDF_P = 255;
|
||||
public static double shooterPIDF_I = 0.0;
|
||||
public static double shooterPIDF_P = 500;
|
||||
public static double shooterPIDF_I = 1;
|
||||
public static double shooterPIDF_D = 0.0;
|
||||
public static double shooterPIDF_F = 75;
|
||||
public static double shooterPIDF_F = 93;
|
||||
|
||||
private double velo = 0.0;
|
||||
private double velo1 = 0.0;
|
||||
@@ -70,8 +72,9 @@ public class Flywheel {
|
||||
|
||||
private double prevF = 0;
|
||||
|
||||
public static double voltagePIDFDifference = 0.8;
|
||||
public void setF(double f){
|
||||
public static double voltagePIDFDifference = 1;
|
||||
public void setF(double voltage){
|
||||
double f = shooterPIDF_F / voltage;
|
||||
if (Math.abs(prevF - f) > voltagePIDFDifference) {
|
||||
shooterPIDF.f = f;
|
||||
robot.shooter1.setPIDFCoefficients(DcMotor.RunMode.RUN_USING_ENCODER, shooterPIDF);
|
||||
@@ -128,5 +131,7 @@ public class Flywheel {
|
||||
|
||||
steady = (Math.abs(commandedVelocity - averageVelocity) < 50);
|
||||
}
|
||||
|
||||
|
||||
public double getShooterPower(){return power;}
|
||||
}
|
||||
@@ -0,0 +1,22 @@
|
||||
package org.firstinspires.ftc.teamcode.utilsv2;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
|
||||
|
||||
public class ParkTilter {
|
||||
Robot robot;
|
||||
public ParkTilter (Robot rob) {
|
||||
this.robot = rob;
|
||||
}
|
||||
|
||||
public void park() {
|
||||
robot.setTilt1Pos(ServoPositions.tilt1_down);
|
||||
robot.setTilt2Pos(ServoPositions.tilt2_down);
|
||||
}
|
||||
|
||||
public void unpark() {
|
||||
robot.setTilt1Pos(ServoPositions.tilt1_up);
|
||||
robot.setTilt2Pos(ServoPositions.tilt2_up);
|
||||
}
|
||||
}
|
||||
@@ -169,7 +169,7 @@ public class Robot {
|
||||
// Voids below are used to minimize hardware calls to minimize loop times
|
||||
|
||||
// Used to cut off digits that are negligible
|
||||
private final int maxDigits = 5;
|
||||
private final int maxDigits = 3;
|
||||
private final int roundingFactor = (int) Math.pow(10, maxDigits);
|
||||
|
||||
private double prevFrontLeftPower = -10.501;
|
||||
|
||||
@@ -1,9 +1,12 @@
|
||||
package org.firstinspires.ftc.teamcode.utilsv2;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.utilsv2.Flywheel.*;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.pedropathing.follower.Follower;
|
||||
|
||||
|
||||
@Config
|
||||
public class Shooter {
|
||||
|
||||
Robot robot;
|
||||
@@ -15,18 +18,21 @@ public class Shooter {
|
||||
double goalY = 0.0;
|
||||
double obeliskX = 72;
|
||||
double obeliskY = 144;
|
||||
double turretGoalX = 0;
|
||||
double turretGoalY = 0;
|
||||
|
||||
private boolean red = true;
|
||||
public static boolean manualFlywheel = false;
|
||||
|
||||
|
||||
Follower follow;
|
||||
|
||||
public Shooter(Robot rob, MultipleTelemetry TELE, Follower follower, boolean redAlliance, Turret turret, Flywheel flywheel) {
|
||||
public Shooter(Robot rob, MultipleTelemetry TELE, Follower follower, boolean redAlliance, Turret turret, Flywheel flywheel, VelocityCommander com) {
|
||||
this.robot = rob;
|
||||
this.fly = flywheel;
|
||||
this.turr = turret;
|
||||
this.follow = follower;
|
||||
this.commander = new VelocityCommander();
|
||||
this.commander = com;
|
||||
|
||||
setRedAlliance(redAlliance);
|
||||
|
||||
@@ -37,10 +43,13 @@ public class Shooter {
|
||||
|
||||
if (this.red) {
|
||||
goalX = 144;
|
||||
turretGoalX = 136;
|
||||
} else {
|
||||
goalX = 0;
|
||||
turretGoalX = 8;
|
||||
}
|
||||
goalY = 144;
|
||||
turretGoalY = 136;
|
||||
}
|
||||
|
||||
private double flywheelVelocity = 0.0;
|
||||
@@ -74,20 +83,33 @@ public class Shooter {
|
||||
return turr.getObeliskID();
|
||||
}
|
||||
|
||||
|
||||
public void update() {
|
||||
private final double shooterDistFromCenter = 1.545;
|
||||
public void update(double voltage) {
|
||||
|
||||
switch (state) {
|
||||
case NOTHING:
|
||||
break;
|
||||
case MANUAL:
|
||||
manualFlywheel = true;
|
||||
commander.getVeloPredictive(
|
||||
(goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getVelocity().getXComponent(),
|
||||
follow.getAcceleration().getXComponent(),
|
||||
follow.getVelocity().getYComponent(),
|
||||
follow.getAcceleration().getYComponent(),
|
||||
voltage
|
||||
);
|
||||
|
||||
fly.manageFlywheel(flywheelVelocity);
|
||||
fly.setPIDF(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / voltage);
|
||||
turr.manual(turretPosition);
|
||||
break;
|
||||
case TRACK_GOAL:
|
||||
manualFlywheel = false;
|
||||
turr.trackGoal(
|
||||
(follow.getPose().getX() - goalX),
|
||||
(follow.getPose().getY() - goalY),
|
||||
(turretGoalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(turretGoalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getHeading(),
|
||||
follow.getAngularVelocity(),
|
||||
follow.getVelocity().getXComponent(),
|
||||
@@ -96,54 +118,70 @@ public class Shooter {
|
||||
follow.getAcceleration().getYComponent()
|
||||
);
|
||||
|
||||
flywheelVelocity = commander.getVeloPredictive(
|
||||
(follow.getPose().getX() - goalX),
|
||||
(follow.getPose().getY() - goalY),
|
||||
commander.getVeloPredictive(
|
||||
(goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getVelocity().getXComponent(),
|
||||
follow.getAcceleration().getXComponent(),
|
||||
follow.getVelocity().getYComponent(),
|
||||
follow.getAcceleration().getYComponent()
|
||||
follow.getAcceleration().getYComponent(),
|
||||
voltage
|
||||
);
|
||||
|
||||
flywheelVelocity = commander.getPredictedRPM();
|
||||
|
||||
robot.setHoodPos(commander.getHoodPredicted());
|
||||
fly.manageFlywheel(flywheelVelocity);
|
||||
fly.setF(voltage);
|
||||
break;
|
||||
case READ_OBELISK:
|
||||
manualFlywheel = false;
|
||||
turr.trackObelisk(
|
||||
(follow.getPose().getX() - goalX),
|
||||
(follow.getPose().getY() - goalY),
|
||||
(obeliskX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(obeliskY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getHeading()
|
||||
);
|
||||
|
||||
flywheelVelocity = commander.getVeloPredictive(
|
||||
(follow.getPose().getX() - goalX),
|
||||
(follow.getPose().getY() - goalY),
|
||||
commander.getVeloPredictive(
|
||||
(goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getVelocity().getXComponent(),
|
||||
follow.getAcceleration().getXComponent(),
|
||||
follow.getVelocity().getYComponent(),
|
||||
follow.getAcceleration().getYComponent()
|
||||
follow.getAcceleration().getYComponent(),
|
||||
voltage
|
||||
);
|
||||
|
||||
flywheelVelocity = commander.getPredictedRPM();
|
||||
|
||||
fly.manageFlywheel(flywheelVelocity);
|
||||
fly.setF(voltage);
|
||||
break;
|
||||
|
||||
case MANUAL_TURRET_TRACK_FLY:
|
||||
manualFlywheel = false;
|
||||
turr.manual(turretPosition);
|
||||
flywheelVelocity = commander.getVeloPredictive(
|
||||
(follow.getPose().getX() - goalX),
|
||||
(follow.getPose().getY() - goalY),
|
||||
commander.getVeloPredictive(
|
||||
(goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getVelocity().getXComponent(),
|
||||
follow.getAcceleration().getXComponent(),
|
||||
follow.getVelocity().getYComponent(),
|
||||
follow.getAcceleration().getYComponent()
|
||||
follow.getAcceleration().getYComponent(),
|
||||
voltage
|
||||
);
|
||||
|
||||
flywheelVelocity = commander.getPredictedRPM();
|
||||
robot.setHoodPos(commander.getHoodPredicted());
|
||||
|
||||
fly.manageFlywheel(flywheelVelocity);
|
||||
break;
|
||||
|
||||
case MANUAL_FLYWHEEL_TRACK_TURR:
|
||||
manualFlywheel = true;
|
||||
turr.trackGoal(
|
||||
(follow.getPose().getX() - goalX),
|
||||
(follow.getPose().getY() - goalY),
|
||||
(turretGoalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(turretGoalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getHeading(),
|
||||
follow.getAngularVelocity(),
|
||||
follow.getVelocity().getXComponent(),
|
||||
@@ -151,11 +189,25 @@ public class Shooter {
|
||||
follow.getVelocity().getYComponent(),
|
||||
follow.getAcceleration().getYComponent()
|
||||
);
|
||||
commander.getVeloPredictive(
|
||||
(goalX - follow.getPose().getX() - shooterDistFromCenter*Math.cos(follow.getHeading())),
|
||||
(goalY - follow.getPose().getY() - shooterDistFromCenter*Math.sin(follow.getHeading())),
|
||||
follow.getVelocity().getXComponent(),
|
||||
follow.getAcceleration().getXComponent(),
|
||||
follow.getVelocity().getYComponent(),
|
||||
follow.getAcceleration().getYComponent(),
|
||||
voltage
|
||||
);
|
||||
fly.manageFlywheel(flywheelVelocity);
|
||||
fly.setPIDF(shooterPIDF_P, shooterPIDF_I, shooterPIDF_D, shooterPIDF_F / voltage);
|
||||
fly.setF(voltage);
|
||||
break;
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
public double getDistance(){return commander.getDistance();}
|
||||
|
||||
|
||||
}
|
||||
|
||||
@@ -1,24 +1,191 @@
|
||||
package org.firstinspires.ftc.teamcode.utilsv2;
|
||||
|
||||
import android.health.connect.datatypes.units.Velocity;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.hardware.NormalizedRGBA;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
|
||||
import org.firstinspires.ftc.teamcode.tests.NewShooterTest;
|
||||
|
||||
@Config
|
||||
public class SpindexerTransferIntake {
|
||||
|
||||
private final Robot robot;
|
||||
|
||||
public SpindexerTransferIntake(Robot rob, MultipleTelemetry TELE) {
|
||||
VelocityCommander commander;
|
||||
|
||||
private MultipleTelemetry TELE;
|
||||
|
||||
public SpindexerTransferIntake(Robot rob, MultipleTelemetry tele, VelocityCommander com) {
|
||||
this.robot = rob;
|
||||
this.commander = com;
|
||||
this.TELE = tele;
|
||||
}
|
||||
|
||||
private final double sensorDistanceThreshold = 4.0;
|
||||
private final long pulseTime = 50; // ms
|
||||
public enum DesiredPattern {
|
||||
PPG,
|
||||
PGP,
|
||||
GPP
|
||||
}
|
||||
|
||||
public enum SortedShootState {
|
||||
IDLE,
|
||||
|
||||
MOVE_TO_1,
|
||||
WAIT_FOR_1,
|
||||
SHOOT_1,
|
||||
RETRACT_1,
|
||||
|
||||
MOVE_TO_2,
|
||||
WAIT_FOR_2,
|
||||
SHOOT_2,
|
||||
RETRACT_2,
|
||||
|
||||
MOVE_TO_3,
|
||||
WAIT_FOR_3,
|
||||
SHOOT_3,
|
||||
RETRACT_3,
|
||||
|
||||
DONE
|
||||
}
|
||||
|
||||
int[] shootOrder = {0, 1, 2};
|
||||
private final double sensorDistanceThreshold = 6.0;
|
||||
private final long pulseTime = 100; // ms
|
||||
|
||||
private DesiredPattern desiredPattern = DesiredPattern.GPP;
|
||||
|
||||
private SortedShootState shootState = SortedShootState.IDLE;
|
||||
private long shootStateStartTime = System.currentTimeMillis();
|
||||
|
||||
private void setShootState(SortedShootState newState) {
|
||||
shootState = newState;
|
||||
shootStateStartTime = System.currentTimeMillis();
|
||||
}
|
||||
|
||||
private long shootStateTime() {
|
||||
return System.currentTimeMillis() - shootStateStartTime;
|
||||
}
|
||||
|
||||
private int[] buildShootOrder(
|
||||
BallStates[] loaded,
|
||||
DesiredPattern desired) {
|
||||
|
||||
BallStates[] target;
|
||||
|
||||
switch (desired) {
|
||||
case PPG:
|
||||
target = new BallStates[]{
|
||||
BallStates.PURPLE,
|
||||
BallStates.PURPLE,
|
||||
BallStates.GREEN
|
||||
};
|
||||
break;
|
||||
|
||||
case PGP:
|
||||
target = new BallStates[]{
|
||||
BallStates.PURPLE,
|
||||
BallStates.GREEN,
|
||||
BallStates.PURPLE
|
||||
};
|
||||
break;
|
||||
|
||||
default: // GPP
|
||||
target = new BallStates[]{
|
||||
BallStates.GREEN,
|
||||
BallStates.PURPLE,
|
||||
BallStates.PURPLE
|
||||
};
|
||||
}
|
||||
|
||||
int[] order = new int[3];
|
||||
boolean[] used = new boolean[3];
|
||||
|
||||
// first pass: exact color matches
|
||||
for (int i = 0; i < 3; i++) {
|
||||
|
||||
order[i] = -1;
|
||||
|
||||
for (int slot = 0; slot < 3; slot++) {
|
||||
|
||||
if (!used[slot]
|
||||
&& loaded[slot] == target[i]) {
|
||||
|
||||
order[i] = slot;
|
||||
used[slot] = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// second pass: fill leftovers
|
||||
for (int i = 0; i < 3; i++) {
|
||||
|
||||
if (order[i] != -1)
|
||||
continue;
|
||||
|
||||
for (int slot = 0; slot < 3; slot++) {
|
||||
|
||||
if (!used[slot]) {
|
||||
order[i] = slot;
|
||||
used[slot] = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return order;
|
||||
}
|
||||
|
||||
private void moveToSlot(int slot) {
|
||||
|
||||
switch (slot) {
|
||||
|
||||
case 0:
|
||||
robot.setSpinPos(
|
||||
ServoPositions.spindexer_A1
|
||||
);
|
||||
break;
|
||||
|
||||
case 1:
|
||||
robot.setSpinPos(
|
||||
ServoPositions.spindexer_A2
|
||||
);
|
||||
break;
|
||||
|
||||
case 2:
|
||||
robot.setSpinPos(
|
||||
ServoPositions.spindexer_A3
|
||||
);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
public enum SortedIntakeStates {
|
||||
NOTHING,
|
||||
IDLE,
|
||||
INTAKE_1,
|
||||
DELAY_1,
|
||||
INTAKE_2,
|
||||
DELAY_2,
|
||||
INTAKE_3,
|
||||
REVERSE,
|
||||
|
||||
}
|
||||
|
||||
public enum SpindexerMode {
|
||||
RAPID,
|
||||
SORTED
|
||||
SORTED,
|
||||
SHOOT_SORTED
|
||||
}
|
||||
|
||||
public enum BallStates {
|
||||
GREEN,
|
||||
PURPLE,
|
||||
UNKNOWN
|
||||
}
|
||||
|
||||
public enum RapidMode {
|
||||
@@ -34,12 +201,36 @@ public class SpindexerTransferIntake {
|
||||
|
||||
private SpindexerMode mode = SpindexerMode.RAPID;
|
||||
private RapidMode rapidMode = RapidMode.INTAKE;
|
||||
private SortedIntakeStates sortedIntakeStates = SortedIntakeStates.IDLE;
|
||||
private BallStates[] ballColors = {BallStates.UNKNOWN, BallStates.UNKNOWN, BallStates.UNKNOWN};
|
||||
private final double greenThresh = 0.39;
|
||||
private final double spinMovementTime = 250;
|
||||
|
||||
/**
|
||||
* Time when current state was entered.
|
||||
*/
|
||||
private long stateStartTime = System.currentTimeMillis();
|
||||
private long sortedStateStartTime = System.currentTimeMillis();
|
||||
|
||||
public void setDesiredPattern(DesiredPattern pattern) {
|
||||
desiredPattern = pattern;
|
||||
}
|
||||
|
||||
public void startSortedShoot() {
|
||||
|
||||
shootOrder = buildShootOrder(
|
||||
ballColors,
|
||||
desiredPattern
|
||||
);
|
||||
|
||||
setShootState(
|
||||
SortedShootState.IDLE
|
||||
);
|
||||
|
||||
setSpindexerMode(
|
||||
SpindexerMode.SHOOT_SORTED
|
||||
);
|
||||
}
|
||||
public void setRapidMode(RapidMode newMode) {
|
||||
if (rapidMode != newMode) {
|
||||
rapidMode = newMode;
|
||||
@@ -47,11 +238,18 @@ public class SpindexerTransferIntake {
|
||||
}
|
||||
}
|
||||
|
||||
public void setSortedIntakeMode(SortedIntakeStates newMode) {
|
||||
if (sortedIntakeStates != newMode) {
|
||||
sortedIntakeStates = newMode;
|
||||
sortedStateStartTime = System.currentTimeMillis();
|
||||
}
|
||||
}
|
||||
|
||||
public void setSpindexerMode(SpindexerMode spindexerMode) {
|
||||
this.mode = spindexerMode;
|
||||
}
|
||||
|
||||
public RapidMode getRapidState(){
|
||||
public RapidMode getRapidState() {
|
||||
return this.rapidMode;
|
||||
}
|
||||
|
||||
@@ -59,8 +257,27 @@ public class SpindexerTransferIntake {
|
||||
return System.currentTimeMillis() - stateStartTime;
|
||||
}
|
||||
|
||||
private long sortedStateTime() {
|
||||
return System.currentTimeMillis() - sortedStateStartTime;
|
||||
}
|
||||
|
||||
public void update() {
|
||||
|
||||
TELE.addData("Sorted State", sortedIntakeStates);
|
||||
TELE.addData("Ball0", ballColors[0]);
|
||||
TELE.addData("Ball1", ballColors[1]);
|
||||
TELE.addData("Ball2", ballColors[2]);
|
||||
|
||||
TELE.addData("Shoot0", shootOrder[0]);
|
||||
TELE.addData("Shoot1", shootOrder[1]);
|
||||
TELE.addData("Shoot2", shootOrder[2]);
|
||||
|
||||
TELE.addData("Color0", ballColors[0]);
|
||||
TELE.addData("Color1", ballColors[1]);
|
||||
TELE.addData("Color2", ballColors[2]);
|
||||
|
||||
TELE.addData("Shoot State", shootState);
|
||||
|
||||
switch (mode) {
|
||||
|
||||
case RAPID:
|
||||
@@ -74,13 +291,13 @@ public class SpindexerTransferIntake {
|
||||
case INTAKE:
|
||||
|
||||
robot.setIntakePower(1);
|
||||
robot.setTransferPower(1);
|
||||
robot.setRapidFireBlockerPos(
|
||||
ServoPositions.rapidFireBlocker_Closed
|
||||
);
|
||||
robot.setSpinPos(
|
||||
ServoPositions.spindexer_A2
|
||||
);
|
||||
robot.setTransferPower(-0.7);
|
||||
robot.setTransferServoPos(
|
||||
ServoPositions.transferServo_out
|
||||
);
|
||||
@@ -95,11 +312,10 @@ public class SpindexerTransferIntake {
|
||||
|
||||
case TRANSFER_OFF:
|
||||
|
||||
robot.setTransferPower(0.3);
|
||||
|
||||
if (robot.insideBeam.isPressed() && robot.outsideBeam.isPressed()) {
|
||||
setRapidMode(RapidMode.BEFORE_PULSE_OUT);
|
||||
}
|
||||
robot.setTransferPower(-0.3);
|
||||
|
||||
break;
|
||||
|
||||
@@ -145,9 +361,6 @@ public class SpindexerTransferIntake {
|
||||
|
||||
robot.setIntakePower(1);
|
||||
}
|
||||
|
||||
|
||||
|
||||
break;
|
||||
|
||||
case OPEN_GATE:
|
||||
@@ -160,6 +373,12 @@ public class SpindexerTransferIntake {
|
||||
setRapidMode(RapidMode.SHOOT);
|
||||
}
|
||||
|
||||
if (Shooter.manualFlywheel) {
|
||||
robot.setTransferPower(NewShooterTest.transferPower);
|
||||
} else {
|
||||
robot.setTransferPower(commander.getTransferPow());
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case SHOOT:
|
||||
@@ -170,13 +389,303 @@ public class SpindexerTransferIntake {
|
||||
if (stateTime() >= 400) {
|
||||
setRapidMode(RapidMode.INTAKE);
|
||||
}
|
||||
|
||||
if (Shooter.manualFlywheel) {
|
||||
robot.setTransferPower(NewShooterTest.transferPower);
|
||||
} else {
|
||||
robot.setTransferPower(commander.getTransferPow());
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
break;
|
||||
|
||||
case SORTED:
|
||||
|
||||
// Future sorted-intake logic
|
||||
switch (sortedIntakeStates) {
|
||||
case NOTHING:
|
||||
break;
|
||||
case IDLE:
|
||||
ballColors[0] = BallStates.UNKNOWN;
|
||||
ballColors[1] = BallStates.UNKNOWN;
|
||||
ballColors[2] = BallStates.UNKNOWN;
|
||||
robot.setRapidFireBlockerPos(
|
||||
ServoPositions.rapidFireBlocker_Open
|
||||
);
|
||||
robot.setSpindexBlockerPos(
|
||||
ServoPositions.spindexBlocker_Closed
|
||||
);
|
||||
robot.setSpinPos(
|
||||
ServoPositions.spindexer_A1
|
||||
);
|
||||
robot.setTransferServoPos(
|
||||
ServoPositions.transferServo_out
|
||||
);
|
||||
robot.setIntakePower(1);
|
||||
robot.setTransferPower(-1);
|
||||
if (sortedStateTime() > 200) {
|
||||
setSortedIntakeMode(SortedIntakeStates.INTAKE_1);
|
||||
}
|
||||
break;
|
||||
case INTAKE_1:
|
||||
robot.setIntakePower(1);
|
||||
robot.setTransferPower(-1);
|
||||
if (robot.insideBeam.isPressed() && robot.revSensor.getDistance(DistanceUnit.CM) < sensorDistanceThreshold) {
|
||||
//TODO: ADD DELAY OR AVERGE @ DANIEL
|
||||
NormalizedRGBA revColor = robot.revSensor.getNormalizedColors();
|
||||
if ((revColor.green / (revColor.red + revColor.blue + revColor.green)) > greenThresh) {
|
||||
ballColors[0] = BallStates.GREEN;
|
||||
} else {
|
||||
ballColors[0] = BallStates.PURPLE;
|
||||
}
|
||||
robot.setSpinPos(ServoPositions.spindexer_A2);
|
||||
setSortedIntakeMode(SortedIntakeStates.DELAY_1);
|
||||
}
|
||||
break;
|
||||
case DELAY_1:
|
||||
robot.setSpinPos(ServoPositions.spindexer_A2);
|
||||
if (sortedStateTime() > spinMovementTime) {
|
||||
setSortedIntakeMode(SortedIntakeStates.INTAKE_2);
|
||||
}
|
||||
break;
|
||||
case INTAKE_2:
|
||||
robot.setIntakePower(1);
|
||||
robot.setTransferPower(-1);
|
||||
if (robot.insideBeam.isPressed() && robot.revSensor.getDistance(DistanceUnit.CM) < sensorDistanceThreshold) {
|
||||
NormalizedRGBA revColor = robot.revSensor.getNormalizedColors();
|
||||
if ((revColor.green / (revColor.red + revColor.blue + revColor.green)) > greenThresh) {
|
||||
ballColors[1] = BallStates.GREEN;
|
||||
} else {
|
||||
ballColors[1] = BallStates.PURPLE;
|
||||
}
|
||||
robot.setSpinPos(ServoPositions.spindexer_A3);
|
||||
setSortedIntakeMode(SortedIntakeStates.DELAY_2);
|
||||
}
|
||||
break;
|
||||
case DELAY_2:
|
||||
|
||||
robot.setSpinPos(
|
||||
ServoPositions.spindexer_A3
|
||||
);
|
||||
|
||||
if (sortedStateTime() > spinMovementTime) {
|
||||
setSortedIntakeMode(
|
||||
SortedIntakeStates.INTAKE_3
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case INTAKE_3:
|
||||
robot.setIntakePower(1);
|
||||
robot.setTransferPower(-1);
|
||||
if (robot.insideBeam.isPressed() && robot.revSensor.getDistance(DistanceUnit.CM) < sensorDistanceThreshold) {
|
||||
NormalizedRGBA revColor = robot.revSensor.getNormalizedColors();
|
||||
if ((revColor.green / (revColor.red + revColor.blue + revColor.green)) > greenThresh) {
|
||||
ballColors[2] = BallStates.GREEN;
|
||||
} else {
|
||||
ballColors[2] = BallStates.PURPLE;
|
||||
}
|
||||
setSortedIntakeMode(SortedIntakeStates.REVERSE);
|
||||
|
||||
}
|
||||
break;
|
||||
case REVERSE:
|
||||
robot.setTransferPower(-0.3);
|
||||
robot.setIntakePower(-0.1);
|
||||
}
|
||||
|
||||
|
||||
break;
|
||||
case SHOOT_SORTED:
|
||||
|
||||
robot.setTransferPower(commander.getTransferPow());
|
||||
|
||||
|
||||
switch (shootState) {
|
||||
case IDLE:
|
||||
shootOrder = buildShootOrder(
|
||||
ballColors,
|
||||
desiredPattern
|
||||
);
|
||||
|
||||
setShootState(SortedShootState.MOVE_TO_1);
|
||||
mode = SpindexerMode.SHOOT_SORTED;
|
||||
break;
|
||||
case MOVE_TO_1:
|
||||
|
||||
moveToSlot(shootOrder[0]);
|
||||
robot.setRapidFireBlockerPos(
|
||||
ServoPositions.rapidFireBlocker_Open
|
||||
);
|
||||
robot.setSpindexBlockerPos(
|
||||
ServoPositions.spindexBlocker_Closed
|
||||
);
|
||||
|
||||
|
||||
setShootState(
|
||||
SortedShootState.WAIT_FOR_1
|
||||
);
|
||||
|
||||
break;
|
||||
case WAIT_FOR_1:
|
||||
|
||||
if (shootStateTime() > 250) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.SHOOT_1
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
case SHOOT_1:
|
||||
|
||||
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
|
||||
robot.setTransferServoPos(ServoPositions.transferServo_in);
|
||||
|
||||
|
||||
if (shootStateTime() > 300) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.RETRACT_1
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case RETRACT_1:
|
||||
|
||||
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Closed);
|
||||
robot.setTransferServoPos(ServoPositions.transferServo_out);
|
||||
|
||||
if (shootStateTime() > 150) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.MOVE_TO_2
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case MOVE_TO_2:
|
||||
|
||||
moveToSlot(shootOrder[1]);
|
||||
|
||||
setShootState(
|
||||
SortedShootState.WAIT_FOR_2
|
||||
);
|
||||
|
||||
break;
|
||||
case WAIT_FOR_2:
|
||||
|
||||
if (shootStateTime() > 250) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.SHOOT_2
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case SHOOT_2:
|
||||
|
||||
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
|
||||
robot.setTransferServoPos(ServoPositions.transferServo_in);
|
||||
|
||||
if (shootStateTime() > 300) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.RETRACT_2
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case RETRACT_2:
|
||||
|
||||
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Closed);
|
||||
robot.setTransferServoPos(ServoPositions.transferServo_out);
|
||||
|
||||
|
||||
if (shootStateTime() > 150) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.MOVE_TO_3
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case MOVE_TO_3:
|
||||
|
||||
moveToSlot(shootOrder[2]);
|
||||
|
||||
setShootState(
|
||||
SortedShootState.WAIT_FOR_3
|
||||
);
|
||||
|
||||
break;
|
||||
case WAIT_FOR_3:
|
||||
|
||||
if (shootStateTime() > 250) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.SHOOT_3
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case SHOOT_3:
|
||||
|
||||
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
|
||||
robot.setTransferServoPos(ServoPositions.transferServo_in);
|
||||
|
||||
if (shootStateTime() > 300) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.RETRACT_3
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case RETRACT_3:
|
||||
|
||||
robot.setTransferServoPos(ServoPositions.transferServo_out);
|
||||
|
||||
if (shootStateTime() > 150) {
|
||||
|
||||
setShootState(
|
||||
SortedShootState.DONE
|
||||
);
|
||||
}
|
||||
|
||||
break;
|
||||
case DONE:
|
||||
|
||||
robot.setRapidFireBlockerPos(
|
||||
ServoPositions.rapidFireBlocker_Open
|
||||
);
|
||||
robot.setSpindexBlockerPos(
|
||||
ServoPositions.spindexBlocker_Closed
|
||||
);
|
||||
robot.setSpinPos(
|
||||
ServoPositions.spindexer_A1
|
||||
);
|
||||
robot.setTransferServoPos(
|
||||
ServoPositions.transferServo_out
|
||||
);
|
||||
robot.setIntakePower(1);
|
||||
robot.setTransferPower(-1);
|
||||
|
||||
if (shootStateTime() > 250) {
|
||||
|
||||
setSortedIntakeMode(
|
||||
SortedIntakeStates.IDLE
|
||||
);
|
||||
|
||||
mode = SpindexerMode.SORTED;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
}
|
||||
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
@@ -83,7 +83,7 @@ public class Turret {
|
||||
robot.setTurretPos(pos);
|
||||
|
||||
}
|
||||
|
||||
// 1.545
|
||||
|
||||
public void trackGoal(double dx, double dy, double h, double hVel, double xVel, double xAcc, double yVel, double yAcc) {
|
||||
// dx, dy, dz is target - robot
|
||||
|
||||
@@ -1,34 +1,117 @@
|
||||
package org.firstinspires.ftc.teamcode.utilsv2;
|
||||
|
||||
import com.acmerobotics.dashboard.config.Config;
|
||||
|
||||
@Config
|
||||
public class VelocityCommander {
|
||||
private final double goalH = 20.0; //TODO: Tune
|
||||
private final double xVelK = 0; // TODO: Tune
|
||||
private final double xAccK = 0; // TODO: Tune
|
||||
private final double yVelK = 0; // TODO: Tune
|
||||
private final double yAccK = 0; // TODO: Tune
|
||||
public static double xVelK = 0.05; // TODO: Tune
|
||||
public static double xAccK = 0.025; // TODO: Tune
|
||||
public static double yVelK = 0.05; // TODO: Tune
|
||||
public static double yAccK = 0.025; // TODO: Tune
|
||||
private double hoodPos = 0.88;
|
||||
private double transferPow = -1;
|
||||
private double velo = 0;
|
||||
|
||||
public VelocityCommander() {
|
||||
|
||||
}
|
||||
public VelocityCommander() {}
|
||||
|
||||
private final double veloA = -2.703087757*Math.pow(10, -14);
|
||||
private final double veloB = 2.904756341*Math.pow(10, -11);
|
||||
private final double veloC = -1.381814293*Math.pow(10, -8);
|
||||
private final double veloD = 0.000003829224585;
|
||||
private final double veloE = -0.000684090204;
|
||||
private final double veloF = 0.0822754689;
|
||||
private final double veloG = -6.743119277;
|
||||
private final double veloH = 371.7359504;
|
||||
private final double veloI = -13189.70958;
|
||||
private final double veloJ = 272005.7124;
|
||||
private final double veloK = -2474581.713;
|
||||
private double distToRPM (double dist){
|
||||
return Math.sqrt(dist*dist + goalH*goalH);
|
||||
//TODO: Add regression here using goalH
|
||||
if (dist < 49) {
|
||||
velo = 2000;
|
||||
} else if (dist > 165){
|
||||
velo = 3760;
|
||||
} else {
|
||||
velo = veloA*Math.pow(dist, 10) +
|
||||
veloB*Math.pow(dist, 9) +
|
||||
veloC*Math.pow(dist, 8) +
|
||||
veloD*Math.pow(dist, 7) +
|
||||
veloE*Math.pow(dist, 6) +
|
||||
veloF*Math.pow(dist, 5) +
|
||||
veloG*Math.pow(dist, 4) +
|
||||
veloH*Math.pow(dist, 3) +
|
||||
veloI*Math.pow(dist, 2) +
|
||||
veloJ*Math.pow(dist, 1) +
|
||||
veloK;
|
||||
velo = Math.max(2000, Math.min(3760, velo));
|
||||
}
|
||||
return velo;
|
||||
}
|
||||
|
||||
private final double hoodA = -4.3276177*Math.pow(10, -13);
|
||||
private final double hoodB = 2.68062979*Math.pow(10, -10);
|
||||
private final double hoodC = -7.12859632*Math.pow(10, -8);
|
||||
private final double hoodD = 0.0000106010785;
|
||||
private final double hoodE = -0.000960693973;
|
||||
private final double hoodF = 0.0540375808;
|
||||
private final double hoodG = -1.82724027;
|
||||
private final double hoodH = 33.4797545;
|
||||
private final double hoodI = -246.888632;
|
||||
private void distToHood (double dist){
|
||||
if (dist > 112){
|
||||
hoodPos = 0.35;
|
||||
} else if (dist < 49){
|
||||
hoodPos = 0.88;
|
||||
} else {
|
||||
hoodPos = hoodA*Math.pow(dist, 8) +
|
||||
hoodB*Math.pow(dist, 7) +
|
||||
hoodC*Math.pow(dist, 6) +
|
||||
hoodD*Math.pow(dist, 5) +
|
||||
hoodE*Math.pow(dist, 4) +
|
||||
hoodF*Math.pow(dist, 3) +
|
||||
hoodG*Math.pow(dist, 2) +
|
||||
hoodH*Math.pow(dist, 1) +
|
||||
hoodI;
|
||||
|
||||
hoodPos = Math.max(0.35, Math.min(0.88, hoodPos));
|
||||
}
|
||||
}
|
||||
public double getHoodPredicted(){
|
||||
return hoodPos;
|
||||
}
|
||||
|
||||
private void distToTransferPow(double dist, double voltage){
|
||||
if (dist < 118){
|
||||
transferPow = -1;
|
||||
} else if (dist < 125){
|
||||
transferPow = -0.7;
|
||||
} else {
|
||||
transferPow = -0.5;
|
||||
}
|
||||
|
||||
// transferPow = Math.max(-0.5, Math.min(-1, transferPow * (14/voltage)));
|
||||
}
|
||||
public double getTransferPow(){return transferPow;}
|
||||
|
||||
// 27
|
||||
public double getVeloStationary (double distance){
|
||||
return distToRPM(distance);
|
||||
}
|
||||
|
||||
public double getVeloPredictive(double dx, double dy, double xVel, double xAcc, double yVel, double yAcc) {
|
||||
double predictedDist = 0;
|
||||
public void getVeloPredictive(double dx, double dy, double xVel, double xAcc, double yVel, double yAcc, double voltage) {
|
||||
|
||||
double predictedDx = dx - (xVel * xVelK) - (0.5 * xAcc * xAccK); // Negative bc dx = target - robot
|
||||
double predictedDy = dy - (yVel * yVelK) - (0.5 * yAcc * yAccK); // Negative bc dy = target - robot
|
||||
|
||||
double predictedDist = Math.sqrt(dx*dx + dy*dy);
|
||||
double goalHeight = 28;
|
||||
predictedDist = Math.sqrt(predictedDx*predictedDx + predictedDy*predictedDy + goalHeight * goalHeight);
|
||||
|
||||
return distToRPM(predictedDist);
|
||||
distToHood(predictedDist);
|
||||
distToTransferPow(predictedDist, voltage);
|
||||
distToRPM(predictedDist);
|
||||
}
|
||||
|
||||
public double getPredictedRPM(){return velo;}
|
||||
|
||||
public double getDistance(){return predictedDist;}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user