Skip to content

Commit f6afa4a

Browse files
committed
Magic Numbers Fix
1 parent 8e66973 commit f6afa4a

File tree

6 files changed

+32
-23
lines changed

6 files changed

+32
-23
lines changed

.github/scripts/constants.py

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,8 @@
99
excused_dirs = [
1010
"bin",
1111
"build",
12-
"src/main/java/frc/robot/pioneersLib"
12+
"src/main/java/frc/robot/pioneersLib",
13+
"src/main/java/frc/robot/teamLib"
1314
]
1415

1516
# Weird stuff that shouldn't go in constants, dont put function/var names in here theyre already checked

src/main/java/frc/robot/Subsystems/Drive/Drive.java

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -123,15 +123,15 @@ public void stop() {
123123
}
124124

125125
public void tankDrive(double leftSpeed, double rightSpeed) {
126-
double left = MathUtil.applyDeadband(leftSpeed, 0.02);
127-
double right = MathUtil.applyDeadband(rightSpeed, 0.02);
126+
double left = MathUtil.applyDeadband(leftSpeed, DEADBAND);
127+
double right = MathUtil.applyDeadband(rightSpeed, DEADBAND);
128128

129129
runClosedLoop(left * MAX_SPEED_METERS_PER_SEC, right * MAX_SPEED_METERS_PER_SEC);
130130
}
131131

132132
public void arcadeDrive(double forward, double rotation) {
133-
double x = MathUtil.applyDeadband(forward, 0.02);
134-
double z = MathUtil.applyDeadband(rotation, 0.02);
133+
double x = MathUtil.applyDeadband(forward, DEADBAND);
134+
double z = MathUtil.applyDeadband(rotation, DEADBAND);
135135

136136
// Calculate speeds
137137
var speeds = DifferentialDrive.arcadeDriveIK(x, z, true);

src/main/java/frc/robot/Subsystems/Drive/DriveConstants.java

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,14 @@ public class DriveConstants {
2222
public static final boolean RIGHT_INVERTED = true;
2323
public static final DCMotor GEARBOX = DCMotor.getCIM(2);
2424

25+
public static final double DEADBAND = 0.02;
26+
public static final double SLOW_MODE_MULTIPLIER = 0.3;
27+
public static final double VOLTAGE_COMPENSATION = 12.0;
28+
public static final double TICKS_PER_REVOLUTION = 1440.0;
29+
public static final double SENSOR_VELOCITY_CONVERSION = 10.0; // ticks per 100ms to per sec
30+
public static final double SIM_UPDATE_PERIOD_SEC = 0.02;
31+
public static final double CURRENT_LIMIT_OFFSET = 15.0;
32+
2533
// Velocity PID configuration
2634
public static final double REAL_KP = 0.0;
2735
public static final double REAL_KD = 0.0;

src/main/java/frc/robot/Subsystems/Drive/DriveIOReal.java

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212

1313
/** This drive implementation is for Talon SRXs driving brushed motors (e.g. CIMS) with encoders. */
1414
public class DriveIOReal implements DriveIO {
15-
private static final double ticksPerRevolution = 1440;
15+
private static final double ticksPerRevolution = TICKS_PER_REVOLUTION;
1616

1717
private final TalonSRX leftLeader = new TalonSRX(LEFT_LEADER_CAN_ID);
1818
private final TalonSRX leftFollower = new TalonSRX(LEFT_FOLLOWER_CAN_ID);
@@ -22,9 +22,9 @@ public class DriveIOReal implements DriveIO {
2222
public DriveIOReal() {
2323
var config = new TalonSRXConfiguration();
2424
config.peakCurrentLimit = CURRENT_LIMIT;
25-
config.continuousCurrentLimit = CURRENT_LIMIT - 15;
25+
config.continuousCurrentLimit = CURRENT_LIMIT - (int)CURRENT_LIMIT_OFFSET;
2626
config.peakCurrentDuration = 250;
27-
config.voltageCompSaturation = 12.0;
27+
config.voltageCompSaturation = VOLTAGE_COMPENSATION;
2828
config.primaryPID.selectedFeedbackSensor = FeedbackDevice.QuadEncoder;
2929

3030
leftLeader.configAllSettings(config);
@@ -47,7 +47,7 @@ public void updateInputs(DriveIOInputs inputs) {
4747
Units.rotationsToRadians(
4848
leftLeader.getSelectedSensorVelocity()
4949
/ ticksPerRevolution
50-
* 10.0); // Raw units are ticks per 100ms :(
50+
* SENSOR_VELOCITY_CONVERSION); // Raw units are ticks per 100ms :(
5151
inputs.leftAppliedVolts = leftLeader.getMotorOutputVoltage();
5252
inputs.leftCurrentAmps =
5353
new double[] {leftLeader.getStatorCurrent(), leftFollower.getStatorCurrent()};
@@ -58,7 +58,7 @@ public void updateInputs(DriveIOInputs inputs) {
5858
Units.rotationsToRadians(
5959
rightLeader.getSelectedSensorVelocity()
6060
/ ticksPerRevolution
61-
* 10.0); // Raw units are ticks per 100ms :(
61+
* SENSOR_VELOCITY_CONVERSION); // Raw units are ticks per 100ms :(
6262
inputs.rightAppliedVolts = rightLeader.getMotorOutputVoltage();
6363
inputs.rightCurrentAmps =
6464
new double[] {rightLeader.getStatorCurrent(), rightFollower.getStatorCurrent()};
@@ -67,8 +67,8 @@ public void updateInputs(DriveIOInputs inputs) {
6767
@Override
6868
public void setVoltage(double leftVolts, double rightVolts) {
6969
// OK to just divide by 12 because voltage compensation is enabled
70-
leftLeader.set(TalonSRXControlMode.PercentOutput, leftVolts / 12.0);
71-
rightLeader.set(TalonSRXControlMode.PercentOutput, rightVolts / 12.0);
70+
leftLeader.set(TalonSRXControlMode.PercentOutput, leftVolts / VOLTAGE_COMPENSATION);
71+
rightLeader.set(TalonSRXControlMode.PercentOutput, rightVolts / VOLTAGE_COMPENSATION);
7272
}
7373

7474
@Override
@@ -79,15 +79,15 @@ public void setVelocity(
7979
TalonSRXControlMode.Velocity,
8080
Units.radiansToRotations(leftRadPerSec)
8181
* ticksPerRevolution
82-
/ 10.0, // Raw units are ticks per 100ms :(
82+
/ SENSOR_VELOCITY_CONVERSION, // Raw units are ticks per 100ms :(
8383
DemandType.ArbitraryFeedForward,
84-
leftFFVolts / 12.0);
84+
leftFFVolts / VOLTAGE_COMPENSATION);
8585
rightLeader.set(
8686
TalonSRXControlMode.Velocity,
8787
Units.radiansToRotations(rightRadPerSec)
8888
* ticksPerRevolution
89-
/ 10.0, // Raw units are ticks per 100ms :(
89+
/ SENSOR_VELOCITY_CONVERSION, // Raw units are ticks per 100ms :(
9090
DemandType.ArbitraryFeedForward,
91-
rightFFVolts / 12.0);
91+
rightFFVolts / VOLTAGE_COMPENSATION);
9292
}
9393
}

src/main/java/frc/robot/Subsystems/Drive/DriveIOSim.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -34,9 +34,9 @@ public void updateInputs(DriveIOInputs inputs) {
3434

3535
// Update simulation state
3636
sim.setInputs(
37-
MathUtil.clamp(leftAppliedVolts, -12.0, 12.0),
38-
MathUtil.clamp(rightAppliedVolts, -12.0, 12.0));
39-
sim.update(0.02);
37+
MathUtil.clamp(leftAppliedVolts, -VOLTAGE_COMPENSATION, VOLTAGE_COMPENSATION),
38+
MathUtil.clamp(rightAppliedVolts, -VOLTAGE_COMPENSATION, VOLTAGE_COMPENSATION));
39+
sim.update(SIM_UPDATE_PERIOD_SEC);
4040

4141
inputs.leftPositionRad = sim.getLeftPositionMeters() / WHEEL_RADIUS_METERS;
4242
inputs.leftVelocityRadPerSec = sim.getLeftVelocityMetersPerSecond() / WHEEL_RADIUS_METERS;

src/main/java/frc/robot/Subsystems/Drive/DriveStates.java

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -8,8 +8,8 @@ public enum DriveStates implements SubsystemStates {
88
double forward = drive.getController().getLeftY();
99
double rotation = drive.getController().getRightX();
1010
if (drive.isSlowMode()) {
11-
forward *= 0.3;
12-
rotation *= 0.3;
11+
forward *= DriveConstants.SLOW_MODE_MULTIPLIER;
12+
rotation *= DriveConstants.SLOW_MODE_MULTIPLIER;
1313
}
1414
drive.arcadeDrive(forward, rotation);
1515
}),
@@ -18,8 +18,8 @@ public enum DriveStates implements SubsystemStates {
1818
double left = drive.getController().getLeftY();
1919
double right = drive.getController().getRightY();
2020
if (drive.isSlowMode()) {
21-
left *= 0.3;
22-
right *= 0.3;
21+
left *= DriveConstants.SLOW_MODE_MULTIPLIER;
22+
right *= DriveConstants.SLOW_MODE_MULTIPLIER;
2323
}
2424
drive.tankDrive(left, right);
2525
});

0 commit comments

Comments
 (0)