@@ -31,9 +31,9 @@ public static final class DriveConstants {
3131 public static final double kMaxAngularSpeed = 2 * Math .PI ; // radians per second
3232
3333 // Chassis configuration
34- public static final double kTrackWidth = Units .inchesToMeters (26.5 );;
34+ public static final double kTrackWidth = Units .inchesToMeters (26.5 );
3535 // Distance between centers of right and left wheels on robot
36- public static final double kWheelBase = Units .inchesToMeters (26.5 );;
36+ public static final double kWheelBase = Units .inchesToMeters (26.5 );
3737 // Distance between front and back wheels on robot
3838 public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics (
3939 new Translation2d (kWheelBase / 2 , kTrackWidth / 2 ),
@@ -62,21 +62,28 @@ 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 kDrivingMotorPinionTeeth = 14 ;
69+
70+ // Invert the turning encoder, since the output shaft rotates in the opposite direction of
71+ // the steering motor in the MAXSwerve Module.
6572 public static final boolean kTurningEncoderInverted = true ;
6673
6774 // Calculations required for driving motor conversion factors and feed forward
68- public static final double kPinionTeeth = 14 ; // Adjust this to match your configuration!
69- public static final double kMotorFreeSpeed = 5676 / 60 ;
70- public static final double kDrivingMotorReduction = 990 / (kPinionTeeth * 15 );
75+ public static final double kDrivingMotorFreeSpeedRps = NeoMotorConstants .kFreeSpeedRpm / 60 ;
7176 public static final double kWheelDiameterMeters = 0.0762 ;
7277 public static final double kWheelCircumferenceMeters = kWheelDiameterMeters * Math .PI ;
73- public static final double kDriveTrainFreeSpeed = (kMotorFreeSpeed * kWheelCircumferenceMeters )
74- / kDrivingMotorReduction ; // calculated motor free speed
78+ // 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15 teeth on the bevel pinion
79+ public static final double kDrivingMotorReduction = (45.0 * 22 ) / (kDrivingMotorPinionTeeth * 15 );
80+ public static final double kDriveWheelFreeSpeedRps = (kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters )
81+ / kDrivingMotorReduction ;
7582
7683 public static final double kDrivingEncoderPositionFactor = (kWheelDiameterMeters * Math .PI )
77- / ( double ) kDrivingMotorReduction ; // meters
84+ / kDrivingMotorReduction ; // meters
7885 public static final double kDrivingEncoderVelocityFactor = ((kWheelDiameterMeters * Math .PI )
79- / ( double ) kDrivingMotorReduction ) / 60.0 ; // meters per second
86+ / kDrivingMotorReduction ) / 60.0 ; // meters per second
8087
8188 public static final double kTurningEncoderPositionFactor = (2 * Math .PI ); // radians
8289 public static final double kTurningEncoderVelocityFactor = (2 * Math .PI ) / 60.0 ; // radians per second
@@ -87,7 +94,7 @@ public static final class ModuleConstants {
8794 public static final double kDrivingP = 0.04 ;
8895 public static final double kDrivingI = 0 ;
8996 public static final double kDrivingD = 0 ;
90- public static final double kDrivingFF = 1 / kDriveTrainFreeSpeed ;
97+ public static final double kDrivingFF = 1 / kDriveWheelFreeSpeedRps ;
9198 public static final double kDrivingMinOutput = -1 ;
9299 public static final double kDrivingMaxOutput = 1 ;
93100
@@ -123,4 +130,8 @@ public static final class AutoConstants {
123130 public static final TrapezoidProfile .Constraints kThetaControllerConstraints = new TrapezoidProfile .Constraints (
124131 kMaxAngularSpeedRadiansPerSecond , kMaxAngularSpeedRadiansPerSecondSquared );
125132 }
133+
134+ public static final class NeoMotorConstants {
135+ public static final double kFreeSpeedRpm = 5676 ;
136+ }
126137}
0 commit comments