Skip to content

Commit 5bab88d

Browse files
Merge branch 'pre-marc' into amp-bar
2 parents c2a8227 + c0e1373 commit 5bab88d

5 files changed

Lines changed: 19 additions & 2 deletions

File tree

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

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,7 @@ 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+
89
public static final int GIT_REVISION = 321;
910
public static final String GIT_SHA = "595783aa307f432a03116af1c4f77599478ee51c";
1011
public static final String GIT_DATE = "2024-08-12 20:54:55 EDT";

src/main/java/frc/robot/Constants.java

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -65,10 +65,15 @@ public static class ModuleConstants {
6565
public static final double DRIVE_GEAR_RATIO = 6.12;
6666
public static final double TURN_GEAR_RATIO = 150.0 / 7.0;
6767

68-
public static final double DRIVE_STATOR_CURRENT_LIMIT = 40.0;
68+
public static final double DRIVE_STATOR_CURRENT_LIMIT = 90.0;
6969
public static final boolean DRIVE_STATOR_CURRENT_LIMIT_ENABLED = true;
70+
public static final double DRIVE_SUPPLY_CURRENT_LIMIT = 42.0;
71+
public static final boolean DRIVE_SUPPLY_CURRENT_LIMIT_ENABLED = true;
72+
7073
public static final double TURN_STATOR_CURRENT_LIMIT = 30.0;
7174
public static final boolean TURN_STATOR_CURRENT_LIMIT_ENABLED = true;
75+
public static final double TURN_SUPPLY_CURRENT_LIMIT = 30.0;
76+
public static final boolean TURN_SUPPLY_CURRENT_LIMIT_ENABLED = true;
7277
}
7378

7479
public static class IntakeConstants {

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

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -115,7 +115,7 @@ public void angleShooter() {
115115
double shootingSpeed = calculateShooterSpeed(Units.metersToFeet(distanceToSpeakerMeter));
116116

117117
shooter.setFlywheelRPMs(shootingSpeed, shootingSpeed + 100);
118-
} else shooter.setFlywheelRPMs(5400 - 200, 5400 - 400);
118+
} else shooter.setFlywheelRPMs(5400 - 100, 5400 - 800);
119119
pivot.setPivotGoal(calculatePivotAngleDeg(distanceToSpeakerMeter));
120120
}
121121

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

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,11 +20,13 @@ public class ScoreAmp extends SequentialCommandGroup {
2020
/** Creates a new ScoreAmp. */
2121
public ScoreAmp(Elevator elevator, Pivot pivot, Shooter shooter, Drive drive) {
2222
addCommands(
23+
amp-bar
2324
new ParallelCommandGroup(
2425
new InstantCommand(() -> elevator.setConstraints(100, 640), elevator),
2526
new InstantCommand(() -> shooter.setFlywheelRPMs(2400, 2400), shooter),
2627
new SetPivotTarget(Constants.PivotConstants.AMP_SETPOINT_DEG, pivot)),
2728
new SetAmpBarTarget(195, 0, elevator),
29+
2830
new SetElevatorTarget(6, 1, elevator));
2931

3032
// addCommands(

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

Lines changed: 9 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -98,6 +98,11 @@ public ModuleIOTalonFX(int index) {
9898
Constants.ModuleConstants.DRIVE_STATOR_CURRENT_LIMIT;
9999
driveConfig.CurrentLimits.StatorCurrentLimitEnable =
100100
Constants.ModuleConstants.DRIVE_STATOR_CURRENT_LIMIT_ENABLED;
101+
driveConfig.CurrentLimits.SupplyCurrentLimit =
102+
Constants.ModuleConstants.DRIVE_SUPPLY_CURRENT_LIMIT;
103+
driveConfig.CurrentLimits.SupplyCurrentLimitEnable =
104+
Constants.ModuleConstants.DRIVE_SUPPLY_CURRENT_LIMIT_ENABLED;
105+
101106
driveTalon.getConfigurator().apply(driveConfig);
102107
setDriveBrakeMode(true);
103108
// setDriveOpenLoopRamp(Constants.SwerveConstants.OPEN_LOOP_RAMP_SEC);
@@ -107,6 +112,10 @@ public ModuleIOTalonFX(int index) {
107112
Constants.ModuleConstants.TURN_STATOR_CURRENT_LIMIT;
108113
turnConfig.CurrentLimits.StatorCurrentLimitEnable =
109114
Constants.ModuleConstants.TURN_STATOR_CURRENT_LIMIT_ENABLED;
115+
turnConfig.CurrentLimits.SupplyCurrentLimit =
116+
Constants.ModuleConstants.TURN_SUPPLY_CURRENT_LIMIT;
117+
turnConfig.CurrentLimits.SupplyCurrentLimitEnable =
118+
Constants.ModuleConstants.TURN_SUPPLY_CURRENT_LIMIT_ENABLED;
110119
turnTalon.getConfigurator().apply(turnConfig);
111120
setTurnBrakeMode(true);
112121

0 commit comments

Comments
 (0)