24 Commits

Author SHA1 Message Date
c36cac12f2 sorting auto is done 2026-06-05 18:25:12 -05:00
f7a9f6aaf5 small tweaks: added current pose telemetry and reduced coasting from limelight track 2026-06-05 14:29:21 -05:00
cc38b98d6f small tweaks: added loop times measurement 2026-06-05 14:19:39 -05:00
755d74a829 small tweaks: added loop times measurement and simplified SortedSpindexerTest 2026-06-05 14:18:47 -05:00
9d29e0b56c tweaks were made and hardware changes are needed 2026-06-04 22:13:49 -05:00
e25b372eca added limelight 2026-06-04 20:57:19 -05:00
3ab905af0c added limelight 2026-06-04 20:38:53 -05:00
58c11f5241 removed bunch of things to remove dash cluter 2026-06-04 20:38:45 -05:00
3afab333ef added delay based on ticks 2026-06-04 19:51:57 -05:00
9b92a59a75 Sorting beta workish 2026-06-04 18:47:23 -05:00
cca86f3691 Added transfer stuff 2026-06-04 18:13:14 -05:00
8c2a655c5c Merge remote-tracking branch 'origin/cowtown-work' into add-sorted-spindexer
# Conflicts:
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utilsv2/SpindexerTransferIntake.java
2026-06-04 18:12:04 -05:00
9a4aca90ba Added sorted modes and shoot 2026-06-04 18:10:31 -05:00
a3479d8816 hello iwnvvtw 2026-06-04 18:08:18 -05:00
e9b9ffc3b8 added transfer power manual command 2026-06-04 17:40:49 -05:00
e7056812b4 shooting is ok but NOT PERFECT 2026-06-04 17:29:14 -05:00
c15b9d58d4 teleop almost there 2026-06-04 16:06:27 -05:00
deefa19be4 added regression 2026-06-04 15:18:08 -05:00
3ae976c16d Merge remote-tracking branch 'origin/add-tilt' into cowtown-work 2026-06-03 15:51:51 -05:00
05f59d1820 Yay 2026-06-03 15:51:03 -05:00
128826f4fd Added tilt thing 2026-06-03 15:26:48 -05:00
a89535830b Lots o changes basically works ig 2026-06-03 15:05:29 -05:00
209c34b3fd Merge remote-tracking branch 'origin/danielv5' into update-teleop
# Conflicts:
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/tests/NewShooterTest.java
#	TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utilsv2/Shooter.java
2026-06-03 14:12:26 -05:00
d8cf594828 Fix some intrinsic bugs, refactor constructor in shooter 2026-06-03 14:08:49 -05:00
34 changed files with 1417 additions and 278 deletions

View File

@@ -337,6 +337,8 @@ public class Auto12BallPedroPathing extends LinearOpMode {
initializePoses();
follower.setPose(startPose);
buildPaths();
// turret.switchPipeline(Turret.PipelineMode.OBELISK);
robot.limelight.start();
sleep(2000);
// turret.setTurret(turrDefault);

View File

@@ -18,11 +18,10 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.constants.ServoPositions;
import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.utilsv2.Flywheel;
import org.firstinspires.ftc.teamcode.utilsv2.*;
import org.firstinspires.ftc.teamcode.utils.MeasuringLoopTimes;
import org.firstinspires.ftc.teamcode.utilsv2.Robot;
import org.firstinspires.ftc.teamcode.utilsv2.Turret;
import java.util.List;
@@ -33,45 +32,52 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
MultipleTelemetry TELE;
Follower follower;
MeasuringLoopTimes loopTimes;
Shooter shooter;
Turret turret;
Flywheel flywheel;
VelocityCommander commander;
SpindexerTransferIntake spindexer;
// Wait Times
public static double shootTime = 2;
public static double openGateTime = 1.5;
public static double sortedShootTime = 2;
public static double rapidWaitTime = 0.25;
public static double rapidShootTime = 1;
public static double openGateTime = 2.5;
public static double pushTime = 2;
// Extra Variables
public static double intakePower = 0.3;
public static double intakePower = 0.5;
double shootX, shootY, shootH;
// Initialize path state machine
private enum PathState {
PUSHBOT, DRIVE_SHOOT0, WAIT_SHOOT0,
PICKUP1, DRIVE_OPENGATE, OPENGATE, DRIVE_SHOOT1, WAIT_SHOOT1,
PICKUP1, OPENGATE, DRIVE_SHOOT1, WAIT_SHOOT1,
DRIVE_PICKUP2, PICKUP2, DRIVE_SHOOT2, WAIT_SHOOT2,
DRIVE_PICKUP3, PICKUP3, DRIVE_SHOOT3, WAIT_SHOOT3
}
PathState pathState = PathState.PUSHBOT;
// Poses
public static double startPoseX = 84, startPoseY = 7, startPoseH = 90;
public static double pushBotX = 94, pushBotY = 9, pushBotH = 100;
public static double shoot0ControlX = 88.29667812142038, shoot0ControlY = 52.03493699885454;
public static double shoot0X = 91, shoot0Y = 80, shoot0H = 0;
public static double pickup1ControlX = 109.29381443298968, pickup1ControlY = 82.70618556701031;
public static double startPoseX = 91.5, startPoseY = 15, startPoseH = 90;
public static double pushBotX = 97, pushBotY = 18, pushBotH = 100;
public static double shoot0ControlX = 94.29667812142038, shoot0ControlY = 55.03493699885454;
public static double shoot0X = 95, shoot0Y = 83, shoot0H = 0;
public static double pickup1X = 126, pickup1Y = 82, pickup1H = 0;
public static double openGateControlX = 109.184421534937, openGateControlY = 74.24455899198165;
public static double openGateX = 129, openGateY = 74, openGateH = 0;
public static double openGateX = 131, openGateY = 74, openGateH = 0;
public static double shoot1ControlX = 112, shoot1ControlY = 75;
public static double shoot1X = 91, shoot1Y = 80, shoot1H = -12;
public static double drivePickup2X = 102, drivePickup2Y = 58.5, drivePickup2H = 0;
public static double shoot1X = 95, shoot1Y = 83, shoot1H = 0;
public static double drivePickup2X = 98, drivePickup2Y = 58.5, drivePickup2H = 0;
public static double pickup2X = 133, pickup2Y = 57, pickup2H = 0;
public static double shoot2ControlX = 102, shoot2ControlY = 63;
public static double shoot2X = 91, shoot2Y = 80, shoot2H = -50;
public static double drivePickup3X = 102, drivePickup3Y = 34.5, drivePickup3H = 0;
public static double shoot2X = 95, shoot2Y = 83, shoot2H = 0;
public static double drivePickup3X = 98, drivePickup3Y = 34.5, drivePickup3H = 0;
public static double pickup3X = 133, pickup3Y = 34.5, pickup3H = 0;
public static double shoot3ControlX = 97.62371134020621, shoot3ControlY = 34.813287514318446;
public static double shoot3X = 84, shoot3Y = 105, shoot3H = -80;
public static double shoot3X = 84, shoot3Y = 120, shoot3H = -90;
Pose startPose, pushBot, shoot0Control, shoot0,
pickup1Control, pickup1, openGateControl, openGate, shoot1Control, shoot1,
pickup1, openGateControl, openGate, shoot1Control, shoot1,
drivePickup2, pickup2, shoot2Control, shoot2,
drivePickup3, pickup3, shoot3Control, shoot3;
private void initializePoses(){
@@ -79,7 +85,6 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
pushBot = new Pose(pushBotX, pushBotY, Math.toRadians(pushBotH));
shoot0Control = new Pose(shoot0ControlX, shoot0ControlY);
shoot0 = new Pose(shoot0X, shoot0Y, Math.toRadians(shoot0H));
pickup1Control = new Pose(pickup1ControlX, pickup1ControlY);
pickup1 = new Pose(pickup1X, pickup1Y, Math.toRadians(pickup1H));
openGateControl = new Pose(openGateControlX, openGateControlY);
openGate = new Pose(openGateX, openGateY, Math.toRadians(openGateH));
@@ -112,7 +117,7 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
.build();
shoot0_pickup1 = follower.pathBuilder()
.addPath(new BezierCurve(shoot0, pickup1Control, pickup1))
.addPath(new BezierLine(shoot0, pickup1))
.setLinearHeadingInterpolation(shoot0.getHeading(), pickup1.getHeading())
.build();
@@ -164,42 +169,46 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
double currentTime = (double) System.currentTimeMillis() / 1000;
switch(pathState){
case PUSHBOT:
spindexer.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.RAPID);
shooter.setFlywheelVelocity(2400);
robot.setHoodPos(0.64);
if (startAuto){
follower.followPath(startPose_pushBot, true);
follower.followPath(startPose_pushBot, false);
startAuto = false;
timeStamp = currentTime;
shootX = shoot0X;
shootY = shoot0Y;
shootH = shoot0H;
}
if (!follower.isBusy()){
if (!follower.isBusy() || currentTime - timeStamp > pushTime){
follower.followPath(pushBot_shoot0, true);
pathState = PathState.DRIVE_SHOOT0;
timeStamp = currentTime;
}
break;
case DRIVE_SHOOT0:
if (!follower.isBusy()){
if (!follower.isBusy() && currentTime - timeStamp > rapidWaitTime){
timeStamp = currentTime;
pathState = PathState.WAIT_SHOOT0;
spindexer.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
}
break;
case WAIT_SHOOT0:
if (currentTime - timeStamp > shootTime){
if (currentTime - timeStamp > rapidShootTime &&
(spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.OPEN_GATE &&
spindexer.getRapidState() != SpindexerTransferIntake.RapidMode.SHOOT)){
follower.followPath(shoot0_pickup1, intakePower, false);
pathState = PathState.PICKUP1;
spindexer.setSpindexerMode(SpindexerTransferIntake.SpindexerMode.SORTED);
}
break;
case PICKUP1:
if (!follower.isBusy()){
follower.followPath(pickup1_openGate, true);
follower.followPath(pickup1_openGate, false);
pathState = PathState.OPENGATE;
shootX = shoot1X;
shootY = shoot1Y;
shootH = shoot1H;
}
break;
case DRIVE_OPENGATE:
if (!follower.isBusy()){
pathState = PathState.OPENGATE;
timeStamp = currentTime;
}
break;
@@ -213,10 +222,11 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
if (!follower.isBusy()){
pathState = PathState.WAIT_SHOOT1;
timeStamp = currentTime;
spindexer.startSortedShoot();
}
break;
case WAIT_SHOOT1:
if (currentTime - timeStamp > shootTime){
if (currentTime - timeStamp > sortedShootTime){
follower.followPath(shoot1_drivePickup2, true);
pathState = PathState.DRIVE_PICKUP2;
}
@@ -240,16 +250,19 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
if (!follower.isBusy()){
pathState = PathState.WAIT_SHOOT2;
timeStamp = currentTime;
spindexer.startSortedShoot();
}
break;
case WAIT_SHOOT2:
if (currentTime - timeStamp > shootTime){
if (currentTime - timeStamp > sortedShootTime){
follower.followPath(shoot2_drivePickup3, true);
pathState = PathState.DRIVE_PICKUP3;
}
break;
case DRIVE_PICKUP3:
if (!follower.isBusy()){
shooter.setFlywheelVelocity(2300);
robot.setHoodPos(0.68);
follower.followPath(drivePickup3_pickup3, intakePower, false);
pathState = PathState.PICKUP3;
}
@@ -266,6 +279,7 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
case DRIVE_SHOOT3:
if (!follower.isBusy()){
pathState = PathState.WAIT_SHOOT3;
spindexer.startSortedShoot();
}
break;
case WAIT_SHOOT3:
@@ -296,19 +310,33 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
}
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
follower = Constants.createFollower(hardwareMap);
sleep(1000);
follower.setStartingPose(new Pose(72,72,0));
loopTimes = new MeasuringLoopTimes();
loopTimes.init();
turret = new Turret(robot);
flywheel = new Flywheel(robot);
commander = new VelocityCommander();
shooter = new Shooter(robot, TELE, follower, Color.redAlliance, turret, flywheel, commander);
spindexer = new SpindexerTransferIntake(robot, TELE, commander);
ParkTilter park = new ParkTilter(robot);
boolean initializeRobot = false;
while (opModeInInit()){
follower.update();
if (gamepad1.squareWasPressed()){
robot.setSpinPos(ServoPositions.spindexer_A2);
robot.setRapidFireBlockerPos(ServoPositions.rapidFireBlocker_Closed);
robot.setSpindexBlockerPos(ServoPositions.spindexBlocker_Open);
}
if (gamepad1.crossWasPressed() && !initializeRobot){
Color.redAlliance = !Color.redAlliance;
shooter.setRedAlliance(Color.redAlliance);
double[] xPoses = {startPoseX, pushBotX, shoot0ControlX, shoot0X,
pickup1ControlX, pickup1X, openGateControlX, openGateX, shoot1ControlX, shoot1X,
pickup1X, openGateControlX, openGateX, shoot1ControlX, shoot1X,
drivePickup2X, pickup2X, shoot2ControlX, shoot2X,
drivePickup3X, pickup3X, shoot3ControlX, shoot3X};
@@ -327,11 +355,25 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
follower.setPose(startPose);
buildPaths();
sleep(2000);
turret.switchPipeline(Turret.PipelineMode.OBELISK);
robot.limelight.start();
limelightUsed = true;
park.unpark();
}
if (initializeRobot){
//add obelisk read here
shooter.setState(Shooter.ShooterState.READ_OBELISK);
int ID = turret.getObeliskID();
spindexer.setDesiredPatternAuto(ID);
TELE.addData("ID", ID);
shooter.update(robot.voltage.getVoltage());
}
TELE.addData("Red Alliance?", Color.redAlliance);
TELE.addData("Initialized Robot? (Don't change this until alliance is selected)", initializeRobot);
TELE.addData("Start Pose", follower.getPose());
TELE.addData("Current LL Pipeline", turret.pipeline());
TELE.update();
}
@@ -339,9 +381,10 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
if (isStopRequested()) return;
limelightUsed = false;
while (opModeIsActive()){
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
shooter.update(robot.voltage.getVoltage());
follower.update();
pathStateMachine();
Pose currentPose = follower.getPose();
@@ -349,6 +392,8 @@ public class Auto12Ball_Back_Sorted extends LinearOpMode {
teleStartPoseY = currentPose.getY();
teleStartPoseH = Math.toDegrees(currentPose.getHeading());
spindexer.update();
for (LynxModule hub : allHubs) {
hub.clearBulkCache();
}

View File

@@ -51,8 +51,7 @@ import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utils.Turret;
@Config
@Autonomous(preselectTeleOp = "TeleopV3")
public class Auto_LT_Close extends LinearOpMode {
public static double shoot0Vel = 2300, shoot0Hood = 0.93;
public static double velGate0Start = 2700, hoodGate0Start = 0.6;

View File

@@ -43,8 +43,7 @@ import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utils.Turret;
@Config
@Autonomous(preselectTeleOp = "TeleopV3")
public class Auto_LT_Far extends LinearOpMode {
public static double shoot0Vel = 3300, shoot0Hood = 0.48;
double xLeave, yLeave, hLeave;

View File

@@ -37,7 +37,6 @@ import org.firstinspires.ftc.teamcode.utils.Turret;
import java.util.Objects;
@Config
public class AutoActions {
Robot robot;
MultipleTelemetry TELE;

View File

@@ -85,9 +85,7 @@ import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utils.Turret;
@Disabled
@Config
@Autonomous(preselectTeleOp = "TeleopV3")
public class Auto_LT_Close_12Ball extends LinearOpMode {
public static double shoot0Vel = 2300, shoot0Hood = 0.93;
public static double autoSpinStartPos = 0.2;

View File

@@ -93,9 +93,7 @@ import org.firstinspires.ftc.teamcode.utils.Turret;
import java.util.Objects;
@Disabled
@Config
@Autonomous(preselectTeleOp = "TeleopV3")
public class Auto_LT_Close_GateOpen extends LinearOpMode {
public static double shoot0Vel = 2300, shoot0Hood = 0.93;
public static double autoSpinStartPos = 0.2;

View File

@@ -82,9 +82,7 @@ import org.firstinspires.ftc.teamcode.utils.Robot;
import org.firstinspires.ftc.teamcode.utils.Servos;
import java.util.List;
@Disabled
@Config
@Autonomous(preselectTeleOp = "TeleopV3")
public class ProtoAutoClose_V3 extends LinearOpMode {
public static double intake1Time = 2.7;
public static double intake2Time = 3.0;

View File

@@ -5,7 +5,7 @@ import com.acmerobotics.dashboard.config.Config;
@Config
public class ServoPositions {
public static double rapidFireBlocker_Closed = 0.35;
public static double rapidFireBlocker_Closed = 0.32;
public static double rapidFireBlocker_Open = 0.5;
public static double spindexBlocker_Closed = 0.31;
@@ -34,9 +34,9 @@ public class ServoPositions {
public static double shootAllSpindexerSpeedIncrease = 0.01;
public static double transferServo_out = 0.57;
public static double transferServo_out = 0.28;
public static double transferServo_in = 0.77;
public static double transferServo_in = 0.54;
public static double hoodAuto = 0.27;

View File

@@ -5,7 +5,7 @@ import com.pedropathing.control.FilteredPIDFCoefficients;
import com.pedropathing.control.PIDFCoefficients;
import com.pedropathing.follower.Follower;
import com.pedropathing.follower.FollowerConstants;
import com.pedropathing.ftc.FollowerBuilder;
import org.firstinspires.ftc.teamcode.pedroPathing.FollowerBuilder;
import com.pedropathing.ftc.drivetrains.MecanumConstants;
import com.pedropathing.ftc.localization.constants.PinpointConstants;
import com.pedropathing.paths.PathConstraints;
@@ -22,7 +22,7 @@ public class Constants {
.lateralZeroPowerAcceleration(-60.876)
.translationalPIDFCoefficients(new PIDFCoefficients(0.15, 0, 0.015, 0.02))
.headingPIDFCoefficients(new PIDFCoefficients(1, 0, 0.02, 0.02))
.drivePIDFCoefficients(new FilteredPIDFCoefficients(0.02, 0, 0.00001, 0.6, 0.015))
.drivePIDFCoefficients(new FilteredPIDFCoefficients(0.013, 0, 0.00001, 0.6, 0.015))
.centripetalScaling(0.0005);
public static MecanumConstants driveConstants = new MecanumConstants()
@@ -51,10 +51,16 @@ public class Constants {
.strafeEncoderDirection(GoBildaPinpointDriver.EncoderDirection.FORWARD);
public static Follower createFollower(HardwareMap hardwareMap) {
return new FollowerBuilder(followerConstants, hardwareMap)
FollowerBuilder followerBuilder;
followerBuilder = new FollowerBuilder(followerConstants, hardwareMap)
.pathConstraints(pathConstraints)
.mecanumDrivetrain(driveConstants)
.pinpointLocalizer(localizerConstants)
.build();
.pinpointLocalizer(localizerConstants);
followerBuilder.resetPinpoint();
followerBuilder.recalibrateIMU();
return followerBuilder.build();
}
}

View File

@@ -0,0 +1,106 @@
package org.firstinspires.ftc.teamcode.pedroPathing;
import com.pedropathing.drivetrain.Drivetrain;
import com.pedropathing.follower.Follower;
import com.pedropathing.follower.FollowerConstants;
import com.pedropathing.ftc.drivetrains.*;
import com.pedropathing.ftc.localization.constants.DriveEncoderConstants;
import com.pedropathing.ftc.localization.constants.OTOSConstants;
import com.pedropathing.ftc.localization.constants.PinpointConstants;
import com.pedropathing.ftc.localization.constants.ThreeWheelConstants;
import com.pedropathing.ftc.localization.constants.ThreeWheelIMUConstants;
import com.pedropathing.ftc.localization.constants.TwoWheelConstants;
import com.pedropathing.ftc.localization.localizers.DriveEncoderLocalizer;
import com.pedropathing.ftc.localization.localizers.OTOSLocalizer;
import com.pedropathing.ftc.localization.localizers.PinpointLocalizer;
import com.pedropathing.ftc.localization.localizers.ThreeWheelIMULocalizer;
import com.pedropathing.ftc.localization.localizers.ThreeWheelLocalizer;
import com.pedropathing.ftc.localization.localizers.TwoWheelLocalizer;
import com.pedropathing.localization.Localizer;
import com.pedropathing.paths.PathConstraints;
import com.qualcomm.robotcore.hardware.HardwareMap;
/** This is the FollowerBuilder.
* It is used to create Followers with a specific drivetrain + localizer without having to use a full constructor
*
* @author Baron Henderson - 20077 The Indubitables
*/
public class FollowerBuilder {
private final FollowerConstants constants;
private PathConstraints constraints;
private final HardwareMap hardwareMap;
private Localizer localizer;
private Drivetrain drivetrain;
public FollowerBuilder(FollowerConstants constants, HardwareMap hardwareMap) {
this.constants = constants;
this.hardwareMap = hardwareMap;
constraints = PathConstraints.defaultConstraints;
}
public FollowerBuilder setLocalizer(Localizer localizer) {
this.localizer = localizer;
return this;
}
public FollowerBuilder driveEncoderLocalizer(DriveEncoderConstants lConstants) {
return setLocalizer(new DriveEncoderLocalizer(hardwareMap, lConstants));
}
public FollowerBuilder OTOSLocalizer(OTOSConstants lConstants) {
return setLocalizer(new OTOSLocalizer(hardwareMap, lConstants));
}
PinpointLocalizer pinpointLocalizer;
public FollowerBuilder pinpointLocalizer(PinpointConstants lConstants) {
pinpointLocalizer = new PinpointLocalizer(hardwareMap, lConstants);
return setLocalizer(pinpointLocalizer);
}
public void resetPinpoint(){
pinpointLocalizer.resetIMU();
}
public void recalibrateIMU(){
pinpointLocalizer.recalibrate();
}
public FollowerBuilder threeWheelIMULocalizer(ThreeWheelIMUConstants lConstants) {
return setLocalizer(new ThreeWheelIMULocalizer(hardwareMap, lConstants));
}
public FollowerBuilder threeWheelLocalizer(ThreeWheelConstants lConstants) {
return setLocalizer(new ThreeWheelLocalizer(hardwareMap, lConstants));
}
public FollowerBuilder twoWheelLocalizer(TwoWheelConstants lConstants) {
return setLocalizer(new TwoWheelLocalizer(hardwareMap, lConstants));
}
public FollowerBuilder setDrivetrain(Drivetrain drivetrain) {
this.drivetrain = drivetrain;
return this;
}
public FollowerBuilder mecanumDrivetrain(MecanumConstants mecanumConstants) {
return setDrivetrain(new Mecanum(hardwareMap, mecanumConstants));
}
@Deprecated
public FollowerBuilder mecanumExDrivetrain(MecanumConstants mecanumConstants) {
return setDrivetrain(new MecanumEx(hardwareMap, mecanumConstants));
}
public FollowerBuilder swerveDrivetrain(SwerveConstants swerveConstants, SwervePod... pods) {
return setDrivetrain(new Swerve(hardwareMap, swerveConstants, pods));
}
public FollowerBuilder pathConstraints(PathConstraints pathConstraints) {
this.constraints = pathConstraints;
PathConstraints.setDefaultConstraints(pathConstraints);
return this;
}
public Follower build() {
return new Follower(constants, localizer, drivetrain, constraints);
}
}

View File

@@ -14,8 +14,11 @@ 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.utils.MeasuringLoopTimes;
import org.firstinspires.ftc.teamcode.utilsv2.*;
import static org.firstinspires.ftc.teamcode.utilsv2.Turret.limelightUsed;
@TeleOp
@Config
public class TeleopV4 extends LinearOpMode {
@@ -25,47 +28,91 @@ public class TeleopV4 extends LinearOpMode {
MultipleTelemetry TELE;
Follower follower;
SpindexerTransferIntake spindexerTransferIntake;
Turret turret;
Flywheel flywheel;
VelocityCommander commander;
ParkTilter parkTilter;
MeasuringLoopTimes loopTimes;
public static Pose relocalizePose = new Pose(128, 83, 0);
@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);
shooter = new Shooter(robot, TELE, follower, Color.redAlliance);
flywheel = new Flywheel(robot);
turret = new Turret(robot);
parkTilter = new ParkTilter(robot);
parkTilter.unpark();
loopTimes = new MeasuringLoopTimes();
loopTimes.init();
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);
turret.switchPipeline(Turret.PipelineMode.TRACKING);
robot.limelight.start();
limelightUsed = true;
waitForStart();
if (isStopRequested()) return;
while (opModeIsActive()) {
//Drivetrain
drivetrain.drive(
-gamepad1.right_stick_y,
gamepad1.right_stick_x,
gamepad1.left_stick_x
);
shooter.update();
if (gamepad1.crossWasPressed()){
follower.setPose(relocalizePose);
gamepad1.rumble(100);
}
follower.update();
Pose currentPose = follower.getPose();
if (gamepad1.dpadLeftWasPressed()){
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
}
if (gamepad1.dpadRightWasPressed()){
shooter.setState(Shooter.ShooterState.TRACK_GOAL);
}
if (shooter.getState() == Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR || shooter.getState() == Shooter.ShooterState.MANUAL){
shooter.setFlywheelVelocity(2500);
robot.setHoodPos(0.6);
robot.setTransferPower(-0.8);
}
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 ||
@@ -76,7 +123,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)) {
@@ -85,14 +132,36 @@ public class TeleopV4 extends LinearOpMode {
);
}
if (gamepad1.yWasPressed()
&& state == SpindexerTransferIntake.RapidMode.HOLD_BALLS) {
spindexerTransferIntake.setRapidMode(
SpindexerTransferIntake.RapidMode.INTAKE
);
if (gamepad1.right_bumper && state != SpindexerTransferIntake.RapidMode.OPEN_GATE && state != SpindexerTransferIntake.RapidMode.SHOOT) {
robot.setIntakePower(1);
}
if (gamepad2.leftBumperWasPressed()){
limelightUsed = false;
} else if (gamepad2.rightBumperWasPressed()){
limelightUsed = true;
}
if (gamepad1.dpad_down){
parkTilter.park();
} else if (gamepad1.dpad_up) {
parkTilter.unpark();
}
loopTimes.loop();
TELE.addData("Loop Time Average", loopTimes.getAvgLoopTime());
TELE.addData("Loop Time Max", loopTimes.getMaxLoopTimeOneMin());
TELE.addData("Loop Time Min", loopTimes.getMinLoopTimeOneMin());
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.addData("Current Position", currentPose);
TELE.addData("Current LL Pipeline", turret.pipeline());
TELE.update();
}

View File

@@ -9,8 +9,7 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.firstinspires.ftc.teamcode.utils.AprilTagWebcam;
import org.firstinspires.ftc.teamcode.utils.Robot;
@Config
@TeleOp
public class AprilTagWebcamExample extends OpMode {
MultipleTelemetry TELE;

View File

@@ -12,8 +12,7 @@ import com.qualcomm.robotcore.hardware.NormalizedRGBA;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
import org.firstinspires.ftc.teamcode.utils.Robot;
@Config
@TeleOp
public class ColorTest extends LinearOpMode {
Robot robot;
MultipleTelemetry TELE;

View File

@@ -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());

View File

@@ -7,8 +7,6 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.firstinspires.ftc.teamcode.utils.Robot;
@Config
@TeleOp
public class MotorDirectionDebugger extends LinearOpMode {
public static double flPower = 0.0;

View File

@@ -1,45 +1,41 @@
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 static org.firstinspires.ftc.teamcode.utilsv2.Turret.limelightUsed;
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.teleop.TeleopV4;
import org.firstinspires.ftc.teamcode.utilsv2.*;
@Config
@TeleOp
@Config
public class NewShooterTest extends LinearOpMode {
Robot robot;
MultipleTelemetry TELE;
Drivetrain drivetrain;
Shooter shooter;
Flywheel rpmFlywheel;
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 = 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.8;
// public static double turretPos = 0.51;
@Override
public void runOpMode() throws InterruptedException {
@@ -48,95 +44,117 @@ public class NewShooterTest extends LinearOpMode {
robot = Robot.getInstance(hardwareMap);
TELE = new MultipleTelemetry(telemetry, FtcDashboard.getInstance().getTelemetry());
shooter = new Shooter(
robot,
TELE,
Constants.createFollower(hardwareMap),
true
TELE = new MultipleTelemetry(
FtcDashboard.getInstance().getTelemetry(), telemetry
);
rpmFlywheel = new Flywheel(robot);
commander = new VelocityCommander();
drivetrain = new Drivetrain(robot, TELE);
follower = Constants.createFollower(hardwareMap);
Pose start = new Pose(teleStartPoseX, teleStartPoseY, Math.toRadians(teleStartPoseH));
follower.setStartingPose(start);
shooter.setState(Shooter.ShooterState.MANUAL);
flywheel = new Flywheel(robot);
turret = new Turret(robot);
parkTilter = new ParkTilter(robot);
parkTilter.unpark();
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);
turret.switchPipeline(Turret.PipelineMode.TRACKING);
robot.limelight.start();
limelightUsed = true;
waitForStart();
if (isStopRequested()) return;
while (opModeIsActive()) {
//Drivetrain
drivetrain.drive(
-gamepad1.right_stick_y,
gamepad1.right_stick_x,
gamepad1.left_stick_x
);
robot.setHoodPos(hoodPos);
shooter.setTurretPosition(turretPos);
shooter.setFlywheelVelocity(flywheel);
rpmFlywheel.manageFlywheel(shooter.getFlywheelVelocity());
double voltage = robot.voltage.getVoltage();
rpmFlywheel.setPIDF(shooterP, shooterI, shooterD, shooterF / voltage);
robot.setSpinPos(ServoPositions.spindexer_A2);
if (intake && !shoot) {
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;
}
if (gamepad1.crossWasPressed()){
follower.setPose(TeleopV4.relocalizePose);
gamepad1.rumble(100);
}
TELE.addData("Flywheel Velocity1", (robot.shooter1.getVelocity() * 60) / 28);
TELE.addData("Flywheel Velocity2", (robot.shooter2.getVelocity() * 60) / 28);
TELE.addData("Flywheel Averag Velocity", rpmFlywheel.getAverageVelocity());
TELE.addData("PIDF Coefficients", Flywheel.shooterPIDF);
TELE.addData("Power", rpmFlywheel.getShooterPower());
TELE.update();
follower.update();
shooter.update();
if (gamepad1.dpadLeftWasPressed()){
shooter.setState(Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR);
}
if (gamepad1.dpadRightWasPressed()){
shooter.setState(Shooter.ShooterState.TRACK_GOAL);
}
if (shooter.getState() == Shooter.ShooterState.MANUAL_FLYWHEEL_TRACK_TURR || shooter.getState() == Shooter.ShooterState.MANUAL){
shooter.setFlywheelVelocity(flywheelVelo);
robot.setHoodPos(hoodPos);
robot.setTransferPower(transferPower);
}
// shooter.setTurretPosition(turretPos);
shooter.update(robot.voltage.getVoltage());
spindexerTransferIntake.update();
if (gamepad2.leftBumperWasPressed()){
limelightUsed = false;
} else if (gamepad2.rightBumperWasPressed()){
limelightUsed = true;
}
SpindexerTransferIntake.RapidMode state = spindexerTransferIntake.getRapidState();
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)) {
spindexerTransferIntake.setRapidMode(SpindexerTransferIntake.RapidMode.OPEN_GATE);
}
if (gamepad1.right_trigger > 0.5 &&
(state == SpindexerTransferIntake.RapidMode.INTAKE ||
state == SpindexerTransferIntake.RapidMode.TRANSFER_OFF)) {
spindexerTransferIntake.setRapidMode(
SpindexerTransferIntake.RapidMode.HOLD_BALLS
);
}
if (gamepad1.right_bumper && state != SpindexerTransferIntake.RapidMode.OPEN_GATE && state != SpindexerTransferIntake.RapidMode.SHOOT) {
robot.setIntakePower(1);
}
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.addData("TX:", turret.getTX());
TELE.update();
}
}
}

View File

@@ -27,8 +27,6 @@ import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utils.Turret;
@Config
@TeleOp
public class ShooterTest extends LinearOpMode {
public static int mode = 1;
public static double parameter = 0.0;

View File

@@ -0,0 +1,125 @@
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.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();
}
}
}

View File

@@ -18,8 +18,6 @@ import org.firstinspires.ftc.teamcode.utils.Spindexer;
import org.firstinspires.ftc.teamcode.utils.Targeting;
import org.firstinspires.ftc.teamcode.utils.Turret;
@Config
@TeleOp
public class SortingTest extends LinearOpMode {
Robot robot;
MultipleTelemetry TELE;

View File

@@ -15,8 +15,6 @@ import org.firstinspires.ftc.teamcode.pedroPathing.Constants;
import org.firstinspires.ftc.teamcode.utils.Robot;
import org.firstinspires.ftc.teamcode.utils.Turret;
@TeleOp
@Config
public class TurretTest extends LinearOpMode {
public static boolean zeroTurr = false;
@Override

View File

@@ -7,7 +7,6 @@ import org.firstinspires.ftc.teamcode.constants.Color;
import org.firstinspires.ftc.teamcode.constants.StateEnums.LightState;
@Config
public final class Light {
private static Light instance;

View File

@@ -43,13 +43,12 @@ public class MeasuringLoopTimes {
public void loop() {
currentTime = getTimeSeconds();
if ((MeasurementStart + 5.0) < currentTime)
if ((MeasurementStart + 60) < currentTime)
{
minLoopTime = 9999999.0;
maxLoopTime = 0.0;
MeasurementStart = currentTime;
avgLoopTime = avgLoopTimeSum / (double) avgLoopTimeTicker;
avgLoopTimeSum = 0.0;
avgLoopTimeTicker = 0;
}
@@ -59,6 +58,7 @@ public class MeasuringLoopTimes {
avgLoopTimeSum += mainLoopTime;
avgLoopTimeTicker++;
avgLoopTime = avgLoopTimeSum / (double) avgLoopTimeTicker;
minLoopTime = Math.min(minLoopTime,mainLoopTime);
maxLoopTime = Math.max(maxLoopTime,mainLoopTime);
}

View File

@@ -10,8 +10,6 @@ import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
@TeleOp
@Config
public class PositionalServoProgrammer extends LinearOpMode {
Robot robot;
MultipleTelemetry TELE;

View File

@@ -16,7 +16,6 @@ import com.qualcomm.robotcore.hardware.VoltageSensor;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;
@Config
public class Robot {
//Initialize Public Components

View File

@@ -6,7 +6,6 @@ import com.acmerobotics.dashboard.config.Config;
import com.arcrobotics.ftclib.controller.PIDFController;
import com.qualcomm.robotcore.hardware.HardwareMap;
@Config
public class Servos {
//PID constants
// TODO: get PIDF constants

View File

@@ -19,7 +19,6 @@ import org.firstinspires.ftc.teamcode.teleop.TeleopV3;
import java.util.ArrayList;
import java.util.List;
@Config
public class Turret {

View File

@@ -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;}
}

View File

@@ -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);
}
}

View File

@@ -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;

View File

@@ -1,12 +1,16 @@
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;
Flywheel fly;
Turret turr;
VelocityCommander commander;
@@ -14,30 +18,38 @@ 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) {
public Shooter(Robot rob, MultipleTelemetry TELE, Follower follower, boolean redAlliance, Turret turret, Flywheel flywheel, VelocityCommander com) {
this.robot = rob;
this.turr = new Turret(rob);
this.fly = flywheel;
this.turr = turret;
this.follow = follower;
this.commander = new VelocityCommander();
this.commander = com;
setRedAlliance(redAlliance);
if (redAlliance) {
goalX = 144;
} else {
goalX = 0;
}
goalY = 144;
}
public void setRedAlliance(boolean input) {
this.red = input;
if (this.red) {
goalX = 144;
turretGoalX = 140;
} else {
goalX = 0;
turretGoalX = 8;
}
goalY = 144;
turretGoalY = 132;
}
private double flywheelVelocity = 0.0;
@@ -59,6 +71,10 @@ public class Shooter {
this.state = shooterState;
}
public ShooterState getState(){
return state;
}
public void setTurretPosition(double input) {
this.turretPosition = input;
}
@@ -66,24 +82,38 @@ public class Shooter {
public void setFlywheelVelocity(double input) {
this.flywheelVelocity = input;
}
public double getFlywheelVelocity(){return this.flywheelVelocity;}
public int getObeliskID() {
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(),
@@ -92,51 +122,68 @@ 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:
turr.trackObelisk(
(follow.getPose().getX() - goalX),
(follow.getPose().getY() - goalY),
follow.getHeading()
);
manualFlywheel = false;
robot.setTurretPos(Turret.neutralPosition);
flywheelVelocity = commander.getVeloPredictive(
(follow.getPose().getX() - goalX),
(follow.getPose().getY() - goalY),
turr.detectObelisk();
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(0);
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(),
@@ -144,10 +191,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();}
}

View File

@@ -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,46 @@ 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 setDesiredPatternAuto(int id) {
if (id == 22){
desiredPattern = DesiredPattern.PGP;
} else if (id == 23){
desiredPattern = DesiredPattern.PPG;
} else {
desiredPattern = DesiredPattern.GPP;
}
}
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 +248,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 +267,29 @@ public class SpindexerTransferIntake {
return System.currentTimeMillis() - stateStartTime;
}
private long sortedStateTime() {
return System.currentTimeMillis() - sortedStateStartTime;
}
private int greenTicks = 0;
private int ballTicks = 0;
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 +303,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 +324,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 +373,6 @@ public class SpindexerTransferIntake {
robot.setIntakePower(1);
}
break;
case OPEN_GATE:
@@ -160,6 +385,12 @@ public class SpindexerTransferIntake {
setRapidMode(RapidMode.SHOOT);
}
if (Shooter.manualFlywheel) {
robot.setTransferPower(NewShooterTest.transferPower);
} else {
robot.setTransferPower(commander.getTransferPow());
}
break;
case SHOOT:
@@ -170,13 +401,333 @@ 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
robot.setRapidFireBlockerPos(ServoPositions.rapidFireBlocker_Open);
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(-0.7);
if (sortedStateTime() > 200) {
setSortedIntakeMode(SortedIntakeStates.INTAKE_1);
}
break;
case INTAKE_1:
robot.setIntakePower(1);
robot.setTransferPower(-0.7);
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) {
greenTicks++;
}
ballTicks++;
if (ballTicks > 15) {
if (greenTicks > 10){
ballColors[0] = BallStates.GREEN;
} else {
ballColors[0] = BallStates.PURPLE;
}
robot.setSpinPos(ServoPositions.spindexer_A2);
setSortedIntakeMode(SortedIntakeStates.DELAY_1);
ballTicks = 0;
greenTicks = 0;
}
}
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) {
greenTicks++;
}
ballTicks++;
if (ballTicks > 15) {
if (greenTicks > 10){
ballColors[1] = BallStates.GREEN;
} else {
ballColors[1] = BallStates.PURPLE;
}
robot.setSpinPos(ServoPositions.spindexer_A3);
setSortedIntakeMode(SortedIntakeStates.DELAY_2);
ballTicks = 0;
greenTicks = 0;
}
}
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) {
greenTicks++;
}
ballTicks++;
if (ballTicks > 15) {
if (greenTicks > 10){
ballColors[2] = BallStates.GREEN;
} else {
ballColors[2] = BallStates.PURPLE;
}
setSortedIntakeMode(SortedIntakeStates.REVERSE);
ballTicks = 0;
greenTicks = 0;
}
}
break;
case REVERSE:
robot.setTransferPower(-0.3);
robot.setIntakePower(-0.1);
break;
}
break;
case SHOOT_SORTED:
robot.setRapidFireBlockerPos(ServoPositions.rapidFireBlocker_Open);
if (Shooter.manualFlywheel) {
robot.setTransferPower(NewShooterTest.transferPower);
} else {
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(-0.7);
if (shootStateTime() > 250) {
setSortedIntakeMode(
SortedIntakeStates.IDLE
);
mode = SpindexerMode.SORTED;
}
break;
}
break;
}
}

View File

@@ -1,11 +1,14 @@
package org.firstinspires.ftc.teamcode.utilsv2;
import com.acmerobotics.dashboard.config.Config;
import com.arcrobotics.ftclib.controller.PIDController;
import com.qualcomm.hardware.limelightvision.LLResult;
import com.qualcomm.hardware.limelightvision.LLResultTypes;
import com.qualcomm.robotcore.util.Range;
import org.firstinspires.ftc.teamcode.constants.Color;
import java.util.List;
@Config
@@ -13,9 +16,22 @@ public class Turret {
Robot robot;
private final double servoTicksPer180 = 0.58;
private final double neutralPosition = 0.51;
public static double neutralPosition = 0.51;
private final double turretMin = 0.05;
private final double turretMax = 0.95;
public static boolean limelightUsed = true;
public static double B_PID_P = 0.0003, B_PID_I = 0.0, B_PID_D = 0.00003;
LLResult result;
PIDController bearingPID;
boolean bearingAligned = false;
public int LL_COAST_TICKS = 5;
public static double TARGET_POSITION_TOLERANCE = 0.5;
public static double alphaTX = 0.5;
private double targetTx = 0;
private double currentTrackOffset = 0;
private double llCoast = 0;
private double servoAngle = 0.51;
double tx = 0.0;
private final double hVelK = 0; // TODO: Tune
private final double xVelK = 0; // TODO: Tune
private final double xAccK = 0; // TODO: Tune
@@ -28,6 +44,7 @@ public class Turret {
public Turret(Robot rob) {
this.robot = rob;
bearingPID = new PIDController(B_PID_P, B_PID_I, B_PID_D);
}
private double wrapAngle(double angle) {
@@ -36,6 +53,43 @@ public class Turret {
return angle;
}
private void limelightRead() { // only for tracking purposes, not general reads
switchPipeline(PipelineMode.TRACKING);
result = robot.limelight.getLatestResult();
tx = 1000;
if (result != null) {
if (result.isValid()) {
tx = result.getTx();
}
}
}
public double getTX(){return tx;}
public enum PipelineMode{
OBELISK,
TRACKING
}
private int prevPipeline = 0;
public void switchPipeline(PipelineMode pipelineMode){
int pipeline = 0;
if (pipelineMode == PipelineMode.OBELISK){
pipeline = 1;
} else if (pipelineMode == PipelineMode.TRACKING){
if (Color.redAlliance){
pipeline = 4;
} else {
pipeline = 2;
}
}
if (pipeline != prevPipeline){
robot.limelight.pipelineSwitch(pipeline);
}
prevPipeline = pipeline;
}
public int pipeline(){return prevPipeline;}
public void trackObelisk(double dx, double dy, double h) {
double heading = wrapAngle(h);
@@ -54,7 +108,6 @@ public class Turret {
robot.setTurretPos(servoAngle);
detectObelisk();
}
@@ -63,32 +116,26 @@ public class Turret {
return obeliskID;
}
private int detectObelisk() {
robot.limelight.pipelineSwitch(1);
LLResult result = robot.limelight.getLatestResult();
public void detectObelisk() {
result = robot.limelight.getLatestResult();
if (result != null && result.isValid()) {
List<LLResultTypes.FiducialResult> fiducials = result.getFiducialResults();
double prevTx = -1000;
for (LLResultTypes.FiducialResult fiducial : fiducials) {
double currentTx = fiducial.getTargetXDegrees();
if (currentTx > prevTx){
obeliskID = fiducial.getFiducialId();
}
obeliskID = fiducial.getFiducialId();
}
}
return obeliskID;
}
public void manual (double pos) {
robot.setTurretPos(pos);
}
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
// h is the raw heading where 0 degrees is positive x in the system of x, y
bearingPID = new PIDController(B_PID_P, B_PID_I, B_PID_D); // Keep when debugging/tuning, comment out when doing teleop
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 predictedH = h + (hVel * hVelK); // Positive bc h = robot heading
@@ -98,11 +145,34 @@ public class Turret {
double fieldRelativeHeading = Math.atan2(predictedDy, predictedDx);
double angleDelta = fieldRelativeHeading - predictedH;
angleDelta = wrapAngle(angleDelta);
angleDelta = wrapAngle(angleDelta) / (2.0 * Math.PI);
double servoTicksFromNeutral = (angleDelta / (2.0 * Math.PI)) * (2.0 * servoTicksPer180);
double bearingOffset = 0;
if (limelightUsed && servoAngle > turretMin && servoAngle < turretMax){
limelightRead();
if (result.isValid() && tx < 100){
targetTx = (tx*alphaTX)+(targetTx*(1-alphaTX));
bearingAligned = Math.abs(targetTx) < TARGET_POSITION_TOLERANCE;
if (!bearingAligned){
bearingOffset = (bearingPID.calculate(targetTx, 0.0));
}
} else {
targetTx = 0;
bearingOffset = 0;
}
currentTrackOffset += bearingOffset;
llCoast = LL_COAST_TICKS;
} else {
if (llCoast <= 0){
currentTrackOffset = 0;
} else {
llCoast--;
}
}
double servoAngle = neutralPosition + servoTicksFromNeutral;
double servoTicksFromNeutral = (angleDelta+currentTrackOffset) * (2.0 * servoTicksPer180);
servoAngle = neutralPosition + servoTicksFromNeutral;
servoAngle = Range.clip(servoAngle, turretMin, turretMax);

View File

@@ -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;}
}