Skip to content

Commit 5ea1d10

Browse files
committed
Slowed down the drivetrain and flywheels and removed the auto selector, elecator, and auto align.
1 parent 63bb3df commit 5ea1d10

3 files changed

Lines changed: 62 additions & 64 deletions

File tree

src/main/java/frc/robot/BuildConstants.java

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -5,12 +5,12 @@ public final class BuildConstants {
55
public static final String MAVEN_GROUP = "";
66
public static final String MAVEN_NAME = "2024RobotCode";
77
public static final String VERSION = "unspecified";
8-
public static final int GIT_REVISION = 358;
9-
public static final String GIT_SHA = "9dfa53aa84b5d502fa0383ae05141e56a77b6c3a";
10-
public static final String GIT_DATE = "2024-10-20 11:22:43 EDT";
8+
public static final int GIT_REVISION = 359;
9+
public static final String GIT_SHA = "63bb3dfb36a7832c8a2307fcd5c600c2f33b9732";
10+
public static final String GIT_DATE = "2024-12-06 17:07:04 EST";
1111
public static final String GIT_BRANCH = "tk-demo-mode";
12-
public static final String BUILD_DATE = "2024-11-27 08:13:20 EST";
13-
public static final long BUILD_UNIX_TIME = 1732713200167L;
12+
public static final String BUILD_DATE = "2024-12-06 17:41:26 EST";
13+
public static final long BUILD_UNIX_TIME = 1733524886836L;
1414
public static final int DIRTY = 1;
1515

1616
private BuildConstants() {}

src/main/java/frc/robot/RobotContainer.java

Lines changed: 56 additions & 58 deletions
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,6 @@
1313

1414
package frc.robot;
1515

16-
import com.pathplanner.lib.auto.AutoBuilder;
1716
import com.pathplanner.lib.auto.NamedCommands;
1817
import edu.wpi.first.math.geometry.Pose2d;
1918
import edu.wpi.first.math.geometry.Rotation2d;
@@ -39,7 +38,6 @@
3938
import frc.robot.commands.AimbotStatic;
4039
import frc.robot.commands.AlignToNoteAuto;
4140
import frc.robot.commands.AngleShooter;
42-
// import frc.robot.commands.AngleShooterShoot;
4341
import frc.robot.commands.DriveCommands;
4442
import frc.robot.commands.PivotIntakeAuto;
4543
import frc.robot.commands.PivotIntakeTele;
@@ -448,18 +446,18 @@ public RobotContainer() {
448446
// Set up auto routines
449447
autos = new SendableChooser<>();
450448

451-
autos.addOption("$s!p-c5-c4", AutoBuilder.buildAuto("$s!p-c5-c4"));
452-
autos.addOption("$s!p-c5-c3", AutoBuilder.buildAuto("$s!p-c5-c3"));
453-
autos.addOption("$s!p-c4-c5", AutoBuilder.buildAuto("$s!p-c4-c5"));
454-
autos.addOption("$s!p-c4-c3", AutoBuilder.buildAuto("$s!p-c4-c3"));
455-
autos.addOption("$s!p-c3-c5", AutoBuilder.buildAuto("$s!p-c3-c5"));
456-
autos.addOption("$s!p-c3-c4", AutoBuilder.buildAuto("$s!p-c3-c4"));
449+
// autos.addOption("$s!p-c5-c4", AutoBuilder.buildAuto("$s!p-c5-c4"));
450+
// autos.addOption("$s!p-c5-c3", AutoBuilder.buildAuto("$s!p-c5-c3"));
451+
// autos.addOption("$s!p-c4-c5", AutoBuilder.buildAuto("$s!p-c4-c5"));
452+
// autos.addOption("$s!p-c4-c3", AutoBuilder.buildAuto("$s!p-c4-c3"));
453+
// autos.addOption("$s!p-c3-c5", AutoBuilder.buildAuto("$s!p-c3-c5"));
454+
// autos.addOption("$s!p-c3-c4", AutoBuilder.buildAuto("$s!p-c3-c4"));
457455

458-
autos.addOption("$c!p-b3-b2-b1", AutoBuilder.buildAuto("$c!p-b3-b2-b1"));
459-
autos.addOption("$c!p-b2-c3", AutoBuilder.buildAuto("$c!p-b2-c3"));
456+
// autos.addOption("$c!p-b3-b2-b1", AutoBuilder.buildAuto("$c!p-b3-b2-b1"));
457+
// autos.addOption("$c!p-b2-c3", AutoBuilder.buildAuto("$c!p-b2-c3"));
460458

461-
autos.addOption("$a!p-b1-c1-c2", AutoBuilder.buildAuto("$a!p-b1-c1-c2"));
462-
autos.addOption("$a!p-b1-c2", AutoBuilder.buildAuto("$a!p-b1-c2"));
459+
// autos.addOption("$a!p-b1-c1-c2", AutoBuilder.buildAuto("$a!p-b1-c1-c2"));
460+
// autos.addOption("$a!p-b1-c2", AutoBuilder.buildAuto("$a!p-b1-c2"));
463461

464462
autoChooser = new LoggedDashboardChooser<>("Auto Choices", autos);
465463

@@ -486,14 +484,14 @@ private void demoControls() {
486484
() -> -driveController.getLeftY(),
487485
() -> -driveController.getLeftX(),
488486
() -> -driveController.getRightX(),
489-
driveLeftBumper,
487+
() -> false,
490488
manipLeftBumper));
491489

492490
driveRightBumper.onTrue(
493491
new SequentialCommandGroup(
494-
new InstantCommand(() -> climbStateMachine.setClimbState(CLIMB_STATES.NONE)),
495-
new InstantCommand(() -> trapStateMachine.setTargetState(TRAP_STATES.PIVOT)),
496-
new SetElevatorTarget(0, 1.5, elevator),
492+
// new InstantCommand(() -> climbStateMachine.setClimbState(CLIMB_STATES.NONE)),
493+
// new InstantCommand(() -> trapStateMachine.setTargetState(TRAP_STATES.PIVOT)),
494+
// new SetElevatorTarget(0, 1.5, elevator),
497495
DriveCommands.intakeCommand(
498496
drive,
499497
shooter,
@@ -532,39 +530,39 @@ private void demoControls() {
532530
drive)
533531
.ignoringDisable(true));
534532

535-
driveLeftBumper.onTrue(
536-
new SequentialCommandGroup(
537-
new InstantCommand(() -> climbStateMachine.setClimbState(CLIMB_STATES.NONE)),
538-
new InstantCommand(() -> trapStateMachine.setTargetState(TRAP_STATES.PIVOT)),
539-
new SetElevatorTarget(0, 1.5, elevator),
540-
DriveCommands.intakeCommand(
541-
drive,
542-
shooter,
543-
pivot,
544-
intake,
545-
led,
546-
driveController,
547-
() -> -driveController.getLeftY(),
548-
() -> -driveController.getLeftX(),
549-
() -> -driveController.getRightX(),
550-
() -> true,
551-
manipLeftBumper)));
552-
driveLeftBumper.onFalse(
553-
new InstantCommand(() -> led.setState(LED_STATE.BLUE))
554-
.andThen(new InstantCommand(() -> intake.changeLEDBoolFalse()))
555-
.andThen(new InstantCommand(() -> shooter.setFeedersRPM(500)))
556-
.andThen(new WaitCommand(0.02))
557-
.andThen(
558-
new ConditionalCommand(
559-
new WaitCommand(0.1),
560-
new WaitCommand(0.06),
561-
() -> (shooter.getLastNoteState() == NoteState.CURRENT)))
562-
.andThen(
563-
new ParallelCommandGroup(
564-
new InstantCommand(() -> intake.stopRollers(), intake),
565-
new InstantCommand(() -> shooter.stopFeeders()),
566-
new SetPivotTarget(Constants.PivotConstants.STOW_SETPOINT_DEG, pivot))
567-
.andThen(new PositionNoteInFeeder(shooter, intake))));
533+
// driveLeftBumper.onTrue(
534+
// new SequentialCommandGroup(
535+
// // new InstantCommand(() -> climbStateMachine.setClimbState(CLIMB_STATES.NONE)),
536+
// // new InstantCommand(() -> trapStateMachine.setTargetState(TRAP_STATES.PIVOT)),
537+
// // new SetElevatorTarget(0, 1.5, elevator),
538+
// DriveCommands.intakeCommand(
539+
// drive,
540+
// shooter,
541+
// pivot,
542+
// intake,
543+
// led,
544+
// driveController,
545+
// () -> -driveController.getLeftY(),
546+
// () -> -driveController.getLeftX(),
547+
// () -> -driveController.getRightX(),
548+
// () -> true,
549+
// manipLeftBumper)));
550+
// driveLeftBumper.onFalse(
551+
// new InstantCommand(() -> led.setState(LED_STATE.BLUE))
552+
// .andThen(new InstantCommand(() -> intake.changeLEDBoolFalse()))
553+
// .andThen(new InstantCommand(() -> shooter.setFeedersRPM(500)))
554+
// .andThen(new WaitCommand(0.02))
555+
// .andThen(
556+
// new ConditionalCommand(
557+
// new WaitCommand(0.1),
558+
// new WaitCommand(0.06),
559+
// () -> (shooter.getLastNoteState() == NoteState.CURRENT)))
560+
// .andThen(
561+
// new ParallelCommandGroup(
562+
// new InstantCommand(() -> intake.stopRollers(), intake),
563+
// new InstantCommand(() -> shooter.stopFeeders()),
564+
// new SetPivotTarget(Constants.PivotConstants.STOW_SETPOINT_DEG, pivot))
565+
// .andThen(new PositionNoteInFeeder(shooter, intake))));
568566

569567
driveLeftTrigger.whileTrue(new PivotIntakeTele(pivot, intake, shooter, led, true, false));
570568
driveLeftTrigger.onFalse(
@@ -577,11 +575,11 @@ private void demoControls() {
577575
new InstantCommand(() -> shooter.stopFeeders(), shooter)
578576
.andThen(new InstantCommand(() -> led.setState(LED_STATE.BLUE)))
579577
.andThen(new SetPivotTarget(Constants.PivotConstants.STOW_SETPOINT_DEG, pivot))
580-
.andThen(
581-
new SetElevatorTarget(
582-
Constants.ElevatorConstants.RETRACT_SETPOINT_INCH,
583-
Constants.ElevatorConstants.THRESHOLD,
584-
elevator))
578+
// .andThen(
579+
// new SetElevatorTarget(
580+
// Constants.ElevatorConstants.RETRACT_SETPOINT_INCH,
581+
// Constants.ElevatorConstants.THRESHOLD,
582+
// elevator))
585583
.andThen(new WaitCommand(0.5))
586584
.andThen(new InstantCommand(shooter::stopFlywheels))
587585
.andThen(new InstantCommand(() -> shooter.turnOffFan(), shooter)));
@@ -590,12 +588,12 @@ private void demoControls() {
590588
.b()
591589
.onTrue(
592590
new SequentialCommandGroup(
593-
new InstantCommand(() -> climbStateMachine.setClimbState(CLIMB_STATES.NONE)),
594-
new InstantCommand(() -> trapStateMachine.setTargetState(TRAP_STATES.PIVOT)),
595-
new SetElevatorTarget(0, 1.5, elevator),
591+
// new InstantCommand(() -> climbStateMachine.setClimbState(CLIMB_STATES.NONE)),
592+
// new InstantCommand(() -> trapStateMachine.setTargetState(TRAP_STATES.PIVOT)),
593+
// new SetElevatorTarget(0, 1.5, elevator),
596594
new InstantCommand(() -> pivot.setShootState(SHOOT_STATE.PIVOT_PRESET)),
597595
new SetPivotTarget(45, pivot),
598-
new InstantCommand(() -> shooter.setFlywheelRPMs(2000, 2300))));
596+
new InstantCommand(() -> shooter.setFlywheelRPMs(1500, 1900))));
599597
driveController
600598
.b()
601599
.onFalse(

src/main/java/frc/robot/subsystems/drive/Drive.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -66,7 +66,7 @@
6666
import org.littletonrobotics.junction.Logger;
6767

6868
public class Drive extends SubsystemBase {
69-
private static final double MAX_LINEAR_SPEED = Constants.SwerveConstants.MAX_LINEAR_SPEED * 0.85;
69+
private static final double MAX_LINEAR_SPEED = Constants.SwerveConstants.MAX_LINEAR_SPEED * 0.4;
7070
private static final double TRACK_WIDTH_X = Constants.SwerveConstants.TRACK_WIDTH_X;
7171
private static final double TRACK_WIDTH_Y = Constants.SwerveConstants.TRACK_WIDTH_Y;
7272
private static final double DRIVE_BASE_RADIUS = Constants.SwerveConstants.DRIVE_BASE_RADIUS;

0 commit comments

Comments
 (0)