Skip to content

Commit 2b21d6b

Browse files
Merge branch 'amp-bar-reamp' into pre-marc
2 parents e4eb82a + a5b463e commit 2b21d6b

4 files changed

Lines changed: 18 additions & 6 deletions

File tree

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

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -5,13 +5,12 @@ public final class BuildConstants {
55
public static final String MAVEN_GROUP = "";
66
public static final String MAVEN_NAME = "2024 Robot Code";
77
public static final String VERSION = "unspecified";
8-
98
public static final int GIT_REVISION = 321;
109
public static final String GIT_SHA = "595783aa307f432a03116af1c4f77599478ee51c";
1110
public static final String GIT_DATE = "2024-08-12 20:54:55 EDT";
12-
public static final String GIT_BRANCH = "amp-bar";
13-
public static final String BUILD_DATE = "2024-08-13 23:59:25 EDT";
14-
public static final long BUILD_UNIX_TIME = 1723607965830L;
11+
public static final String GIT_BRANCH = "amp-bar-reamp";
12+
public static final String BUILD_DATE = "2024-08-14 20:13:53 EDT";
13+
public static final long BUILD_UNIX_TIME = 1723680833471L;
1514
public static final int DIRTY = 1;
1615

1716
private BuildConstants() {}

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

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -917,6 +917,19 @@ private void manipControls() {
917917
new InstantCommand(() -> elevator.setConstraints(30, 85)),
918918
new InstantCommand(() -> shooter.stopFlywheels(), shooter),
919919
new SetPivotTarget(Constants.PivotConstants.STOW_SETPOINT_DEG, pivot))));
920+
// manipAButton.onTrue(
921+
// new InstantCommand(() -> pivot.setShootState(SHOOT_STATE.AMP))
922+
// .andThen(new ScoreAmp(elevator, pivot, shooter, drive)));
923+
924+
// manipAButton.onFalse(
925+
// new InstantCommand(() -> pivot.setShootState(SHOOT_STATE.AIMBOT))
926+
// .andThen(
927+
// new SequentialCommandGroup(
928+
// new InstantCommand(() -> shooter.turnOffFan()),
929+
// new SetElevatorTarget(0, 0.5, elevator),
930+
// new InstantCommand(() -> elevator.setConstraints(30, 85)),
931+
// new InstantCommand(() -> shooter.stopFlywheels(), shooter),
932+
// new SetPivotTarget(Constants.PivotConstants.STOW_SETPOINT_DEG, pivot))));
920933

921934
manipBButton.onTrue(
922935
new ParallelCommandGroup(

src/main/java/frc/robot/commands/ScoreAmp.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@ public ScoreAmp(Elevator elevator, Pivot pivot, Shooter shooter, Drive drive) {
2323
amp-bar
2424
new ParallelCommandGroup(
2525
new InstantCommand(() -> elevator.setConstraints(100, 640), elevator),
26-
new InstantCommand(() -> shooter.setFlywheelRPMs(2400, 2400), shooter),
26+
new InstantCommand(() -> shooter.setFlywheelRPMs(500, 700), shooter),
2727
new SetPivotTarget(Constants.PivotConstants.AMP_SETPOINT_DEG, pivot)),
2828
new SetAmpBarTarget(195, 0, elevator),
2929

src/main/java/frc/robot/subsystems/elevator/AmpBarIOSparkMAX.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@ public class AmpBarIOSparkMAX implements AmpBarIO {
1313
private final CANSparkMax barMotor;
1414
private final SparkPIDController pid;
1515
private double barPositionSetpoint;
16-
private final double gearRatio = 5. / 1.;
16+
private final double gearRatio = 15. / 1.;
1717

1818
public AmpBarIOSparkMAX(int motorID) {
1919

0 commit comments

Comments
 (0)