Skip to content

Commit 9e5e3c3

Browse files
author
NoahAndrews
committed
Improve documentation of motor pinion selection
1 parent e717f12 commit 9e5e3c3

1 file changed

Lines changed: 6 additions & 2 deletions

File tree

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

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -62,14 +62,18 @@ public static final class DriveConstants {
6262
}
6363

6464
public static final class ModuleConstants {
65+
// The MAXSwerve module can be configured with one of three pinion gears: 12T, 13T, or 14T.
66+
// This changes the drive speed of the module (a pinion gear with more teeth will result in a
67+
// robot that drives faster).
68+
public static final int kMotorPinionTeeth = 14;
69+
6570
// Invert the turning encoder, since the output shaft rotates the opposite direction compared to
6671
// the steering motor in the MAXSwerve Module.
6772
public static final boolean kTurningEncoderInverted = true;
6873

6974
// Calculations required for driving motor conversion factors and feed forward
70-
public static final double kPinionTeeth = 14; // Adjust this to match your configuration!
7175
public static final double kDrivingMotorFreeSpeedRps = 5676 / 60;
72-
public static final double kDrivingMotorReduction = 990 / (kPinionTeeth * 15);
76+
public static final double kDrivingMotorReduction = 990 / (kMotorPinionTeeth * 15);
7377
public static final double kWheelDiameterMeters = 0.0762;
7478
public static final double kWheelCircumferenceMeters = kWheelDiameterMeters * Math.PI;
7579
public static final double kDriveTrainFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters)

0 commit comments

Comments
 (0)