From 04cfcfed5506279fbf68388fbe1589aedc0972d0 Mon Sep 17 00:00:00 2001 From: Hayden Heroux Date: Tue, 2 Apr 2024 15:35:44 -0400 Subject: [PATCH] change around states --- simgui.json | 2 +- src/main/java/frc/robot/RobotContainer.java | 1 + src/main/java/frc/robot/shooter/ShooterConstants.java | 3 --- src/main/java/frc/robot/superstructure/Superstructure.java | 2 +- .../java/frc/robot/superstructure/SuperstructureState.java | 5 +---- 5 files changed, 4 insertions(+), 9 deletions(-) diff --git a/simgui.json b/simgui.json index 159d4d1..721b509 100644 --- a/simgui.json +++ b/simgui.json @@ -192,7 +192,7 @@ 0.0, 0.8500000238418579 ], - "height": 338, + "height": 0, "series": [ { "color": [ diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 3908a47..71af5a2 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -86,6 +86,7 @@ private void configureBindings() { operatorController.a().onTrue(superstructure.ampPosition()); operatorController.b().onTrue(superstructure.ampShoot()); + operatorController.x().onTrue(superstructure.stow()); } /** diff --git a/src/main/java/frc/robot/shooter/ShooterConstants.java b/src/main/java/frc/robot/shooter/ShooterConstants.java index 681f4e2..e7088b0 100644 --- a/src/main/java/frc/robot/shooter/ShooterConstants.java +++ b/src/main/java/frc/robot/shooter/ShooterConstants.java @@ -22,9 +22,6 @@ public static class SerializerConstants { /** Constants for the flywheel motor used in the shooter subsystem. */ public static class FlywheelConstants { - /** Velocity to apply while idly spinning up in rotations per second. */ - public static final double IDLE_VELOCITY = 2.5; - /** Velocity to apply while shooting into the speaker in rotations per second. */ public static final double SPEAKER_VELOCITY = 5.65; diff --git a/src/main/java/frc/robot/superstructure/Superstructure.java b/src/main/java/frc/robot/superstructure/Superstructure.java index 760f483..e57d3a3 100644 --- a/src/main/java/frc/robot/superstructure/Superstructure.java +++ b/src/main/java/frc/robot/superstructure/Superstructure.java @@ -181,7 +181,7 @@ public Command intake() { } public Command idle() { - return to(SuperstructureState.IDLE); + return to(SuperstructureState.SPEAKER_SPIN); } public Command shoot() { diff --git a/src/main/java/frc/robot/superstructure/SuperstructureState.java b/src/main/java/frc/robot/superstructure/SuperstructureState.java index 6e7a1c3..2596342 100644 --- a/src/main/java/frc/robot/superstructure/SuperstructureState.java +++ b/src/main/java/frc/robot/superstructure/SuperstructureState.java @@ -26,10 +26,7 @@ public record SuperstructureState( public static final SuperstructureState INTAKE = new SuperstructureState(ShoulderAngleConstants.STOW, RollerConstants.INTAKE_VELOCITY, 0, false, SerializerConstants.INTAKE_VELOCITY); - public static final SuperstructureState IDLE = - new SuperstructureState(ShoulderAngleConstants.STOW, 0, FlywheelConstants.IDLE_VELOCITY, true, 0); - - public static final SuperstructureState SPEAKER_SPIN = new SuperstructureState(ShoulderAngleConstants.STOW, 0, FlywheelConstants.SPEAKER_VELOCITY, false, 0); + public static final SuperstructureState SPEAKER_SPIN = new SuperstructureState(ShoulderAngleConstants.STOW, 0, FlywheelConstants.SPEAKER_VELOCITY, true, 0); public static final SuperstructureState SPEAKER_SHOOT = new SuperstructureState(ShoulderAngleConstants.STOW, 0, FlywheelConstants.SPEAKER_VELOCITY, false, SerializerConstants.SERIALIZE_VELOCITY);